gmapping 分析

2023-10-26

【转载】这一篇先讲我对gmapping源码的理解(难免有错,欢迎指正,相互学习)。

原博客:https://blog.csdn.net/roadseek_zw/article/details/53316177,博客主页:https://blog.csdn.net/roadseek_zw

参考论文: 
Improved Techniques for Grid Mapping with Rao-Blackwellized Particle Filters 
参考博客: 
http://blog.csdn.net/heyijia0327/article/details/40899819 pf原理讲解 
http://blog.csdn.net/u010545732/article/details/17462941 pf代码实现 
http://www.cnblogs.com/yhlx125/p/5634128.html gmapping分析 
http://wenku.baidu.com/view/3a67461550e2524de4187e4d.html?from=search gmapping 分析 
其他参考 : 
http://ishare.iask.sina.com.cn/f/24615049.html

从ros官网上下载 slam_gmapping 包以及在openslam ( http://openslam.org/ )上下载openslam_gmapping包。 
为了方便的阅读源码,这里强力推荐一款源码阅读软件 understand (聪明的你一定找的到资源),可以方便实现各种跳转与生成图、表、树,流程等。 
废话不多说了,开始看源码,对于我这种c++都没有过关的菜鸟,看着大几千行的c++的代码,简直是身体和精神上的蹂躏。 
先说说 slam_gmapping 包与openslam_gmapping包 
进入slam_gmapping 的main.cpp文件的关系,slam_gmapping 是openslam_gampping在ros下的二次封装,你可以直接用这个包,而真正的核心代码实现都在openslam_gampping里面。

进入代码 
先用understand 看看代码的调用关系。 (调用太复杂了,图太大,我就截取了一小部分) 
这里写图片描述 
转到

gn.startLiveSlam();
{
  entropy_publisher_ = private_nh_.advertise<std_msgs::Float64>("entropy", 1, true);
  sst_ = node_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
  sstm_ = node_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
  ss_ = node_.advertiseService("dynamic_map", &SlamGMapping::mapCallback, this);
  scan_filter_sub_ = new message_filters::Subscriber<sensor_msgs::LaserScan>(node_, "scan", 5);
  scan_filter_ = new tf::MessageFilter<sensor_msgs::LaserScan>(*scan_filter_sub_, tf_, odom_frame_, 5);
  scan_filter_->registerCallback(boost::bind(&SlamGMapping::laserCallback, this, _1));

  transform_thread_ = new boost::thread(boost::bind(&SlamGMapping::publishLoop, this, transform_publish_period_));
}

也没写啥,主要就是一些消息的回调以及发布一些服务,重点在

void SlamGMapping::laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
{
  laser_count_++;
   /*每隔throttle_scans_ (默认值 1)帧数据计算一次,限流作用*/
  if ((laser_count_ % throttle_scans_) != 0)  
    return;

  static ros::Time last_map_update(0,0);

  /* We can't initialize the mapper until we've got the first scan */
  if(!got_first_scan_)
  {
 /*一些重要参数的初始化,将slam里的参数传递到 openslam 里 ,设定坐标系,坐标原点,以及采样函数随机种子的初始化,等等
 里面还调用了 GridSlamProcessor::init ,这个初始化了粒子数,子地图大小 */
    if(!initMapper(*scan))
      return;
    got_first_scan_ = true;
  }

  GMapping::OrientedPoint odom_pose;
/**
pay attention: addScan这个函数*要转到pf的核心代码了 ,将调用processScan
*/
  if(addScan(*scan, odom_pose))   
  {
    ROS_DEBUG("scan processed");

    GMapping::OrientedPoint mpose = gsp_->getParticles()[gsp_->getBestParticleIndex()].pose;
    ROS_DEBUG("new best pose: %.3f %.3f %.3f", mpose.x, mpose.y, mpose.theta);
    ROS_DEBUG("odom pose: %.3f %.3f %.3f", odom_pose.x, odom_pose.y, odom_pose.theta);
    ROS_DEBUG("correction: %.3f %.3f %.3f", mpose.x - odom_pose.x, mpose.y - odom_pose.y, mpose.theta - odom_pose.theta);

    tf::Transform laser_to_map = tf::Transform(tf::createQuaternionFromRPY(0, 0, mpose.theta), tf::Vector3(mpose.x, mpose.y, 0.0)).inverse();
    tf::Transform odom_to_laser = tf::Transform(tf::createQuaternionFromRPY(0, 0, odom_pose.theta), tf::Vector3(odom_pose.x, odom_pose.y, 0.0));

    map_to_odom_mutex_.lock();
    map_to_odom_ = (odom_to_laser * laser_to_map).inverse();
    map_to_odom_mutex_.unlock();

    if(!got_map_ || (scan->header.stamp - last_map_update) > map_update_interval_)
    {
      updateMap(*scan);  //更新地图
      last_map_update = scan->header.stamp;
      ROS_DEBUG("Updated the map");
    }
  } else
    ROS_DEBUG("cannot process scan");
}

在 processScan 函数里依次执行了

运动模型

更新t时刻的粒子群,(模型中加入了高斯噪声) 
你要问我是为啥是这样的公式,请自行参考《Probabilistic Robot 》一书的P107页 ,里程计运动模型 
relPose 当前时刻的位姿(x,y,theta) ,m_odoPose 上一时刻的位姿

OrientedPoint 
MotionModel::drawFromMotion(const OrientedPoint& p, const OrientedPoint& pnew, const OrientedPoint& pold) const{
    double sxy=0.3*srr;  //目测是两轮轴间耦合方差,有点诡异???
    OrientedPoint delta=absoluteDifference(pnew, pold);
    OrientedPoint noisypoint(delta);  //噪声估计
    noisypoint.x+=sampleGaussian(srr*fabs(delta.x)+str*fabs(delta.theta)+sxy*fabs(delta.y));
    noisypoint.y+=sampleGaussian(srr*fabs(delta.y)+str*fabs(delta.theta)+sxy*fabs(delta.x));
    noisypoint.theta+=sampleGaussian(stt*fabs(delta.theta)+srt*sqrt(delta.x*delta.x+delta.y*delta.y));
    noisypoint.theta=fmod(noisypoint.theta, 2*M_PI);
    if (noisypoint.theta>M_PI)  
        noisypoint.theta-=2*M_PI;
    return absoluteSum(p,noisypoint);   //叠加噪声
}

计算t-1 —> t 时刻的 位移增量,以及角位移增量

    OrientedPoint move=relPose-m_odoPose;
    move.theta=atan2(sin(move.theta), cos(move.theta));
    m_linearDistance+=sqrt(move*move);
    m_angularDistance+=fabs(move.theta);

    if (! m_count ||m_linearDistance>=m_linearThresholdDistance 
    || m_angularDistance>=m_angularThresholdDistance
    || (period_ >= 0.0 && (reading.getTime() - last_update_time_) > period_))
    {
        //...
    }

if 里面有几个重要的函数,如下

扫描匹配

通过匹配选取最优的粒子,如果匹配失败,则返回一个默认的似然估计 
原理就参考 《Probabilistic Robot》 一书的P143 页 , likelihood_field_range_finder_mode

inline void GridSlamProcessor::scanMatch(const double* plainReading){
  /* sample a new pose from each scan in the reference */

  double sumScore=0;
  for (ParticleVector::iterator it=m_particles.begin(); it!=m_particles.end(); it++){
    OrientedPoint corrected;
    double score, l, s;
/* 计算最优的粒子
optimize 调用了 score 这个函数 (计算粒子得分)
在score 函数里,首先计算障碍物的坐标phit,然后将phit转换成网格坐标iPhit
计算光束上与障碍物相邻的非障碍物网格坐标pfree,pfrree由phit沿激光束方向移动一个网格的距离得到,将pfree转换成网格坐标ipfree(增量,并不是实际值)
在iphit 及其附近8个(m_kernelSize:default=1)栅格(pr,对应自由栅格为pf)搜索最优可能是障碍物的栅格。
最优准则: pr 大于某一阈值,pf小于该阈值,且pr栅格的phit的平均坐标与phit的距离bestMu最小。
得分计算: s +=exp(-1.0/m_gaussianSigma*bestMu*besMu)  参考NDT算法,距离越大,分数越小,分数的较大值集中在距离最小值处,符合正态分布模型
至此 score 函数结束并返回粒子(currentPose)得分,然后回到optimize函数
optimize 干的事就是 currentPose 的位姿进行微调,前、后、左、右、左转、右转 共6次,然后选取得分最高的位姿,返回最终的得分
*/
    score=m_matcher.optimize(corrected, it->map, it->pose, plainReading);
    if (score>m_minimumScore){  //判断得分是否符合要求
      it->pose=corrected;
    } else {
    if (m_infoStream){
      m_infoStream << "Scan Matching Failed, using odometry. Likelihood=" << l <<std::endl;
      m_infoStream << "lp:" << m_lastPartPose.x << " "  << m_lastPartPose.y << " "<< m_lastPartPose.theta <<std::endl;
      m_infoStream << "op:" << m_odoPose.x << " " << m_odoPose.y << " "<< m_odoPose.theta <<std::endl;
    }
    }
/*   likelihoodAndSocre 作用是计算粒子的权重和(l),如果出现匹配失败,则 l=noHit     */
    m_matcher.likelihoodAndScore(s, l, it->map, it->pose, plainReading);
    sumScore+=score;
    it->weight+=l;
    it->weightSum+=l;

/* 计算可活动区域
    //set up the selective copy of the active area
    //by detaching the areas that will be updated
computeActiveArea 用于计算每个粒子相应的位姿所扫描到的区域  
计算过程首先考虑了每个粒子的扫描范围会不会超过子地图的大小,如果会,则resize地图的大小
然后定义了一个activeArea 用于设置可活动区域,调用了gridLine() 函数,这个函数如何实现的,
请参考百度文库那篇介绍。
*/
    m_matcher.invalidateActiveArea();
    m_matcher.computeActiveArea(it->map, it->pose, plainReading);
  }
  if (m_infoStream)
    m_infoStream << "Average Scan Matching Score=" << sumScore/m_particles.size() << std::endl; 
}

权重更新

重采样前更新过一次,重采样后又更新过一次,更新原理,参见论文(表示不是太懂)

void  GridSlamProcessor::updateTreeWeights(bool weightsAlreadyNormalized){

  if (!weightsAlreadyNormalized) {  
    normalize();   //Neff 计算 (论文中公式20)
  }
  resetTree();  //初始化粒子的树节点 权重,访问次数 ,父节点
  propagateWeights();  //为了迭代计算,计算上一次的该粒子的权重   (论文中公式19)
}

重采样

粒子集对目标分布的近似越差,则权重的方差越大,可用Neff来度量,具体原理参见论文,以及白巧克力亦唯心的那篇博客 
代码太长了就不粘贴了 
重采样里还调用了registerScan ,这个函数和computeActive 函数有点像,不同的是,registerScan用于注册每个单元格 
的状态,自由、障碍,调用update()以及entroy()函数更新,最后是障碍物的概率 p=n/visits , 
障碍物的坐标用平均值来算完了后,又有一次权重计算。

至此,processScan 结束,回到laserCallback,还有最优一步updateMap

resample(plainReading, adaptParticles, reading_copy);

地图更新

先得到最优的粒子(用权重和 weightSum判断 ),得到机器人最优轨迹 
地图膨胀更新

void
SlamGMapping::updateMap(const sensor_msgs::LaserScan& scan)
{
  ROS_DEBUG("Update map");
  boost::mutex::scoped_lock map_lock (map_mutex_);
  GMapping::ScanMatcher matcher;
  matcher.setLaserParameters(scan.ranges.size(), &(laser_angles_[0]),
                             gsp_laser_->getPose());
  matcher.setlaserMaxRange(maxRange_);
  matcher.setusableRange(maxUrange_);
  matcher.setgenerateMap(true);
/* 取最优粒子,根据权重和weightSum 判断(最大) */
  GMapping::GridSlamProcessor::Particle best =
          gsp_->getParticles()[gsp_->getBestParticleIndex()];
  std_msgs::Float64 entropy;
  entropy.data = computePoseEntropy();
  if(entropy.data > 0.0)
    entropy_publisher_.publish(entropy);
  if(!got_map_) {
    map_.map.info.resolution = delta_;
    map_.map.info.origin.position.x = 0.0;
    map_.map.info.origin.position.y = 0.0;
    map_.map.info.origin.position.z = 0.0;
    map_.map.info.origin.orientation.x = 0.0;
    map_.map.info.origin.orientation.y = 0.0;
    map_.map.info.origin.orientation.z = 0.0;
    map_.map.info.origin.orientation.w = 1.0;
  } 
  GMapping::Point center;
  center.x=(xmin_ + xmax_) / 2.0;
  center.y=(ymin_ + ymax_) / 2.0;
  GMapping::ScanMatcherMap smap(center, xmin_, ymin_, xmax_, ymax_, 
                                delta_);
  ROS_DEBUG("Trajectory tree:");
  /*得到机器人最优轨迹 */
  for(GMapping::GridSlamProcessor::TNode* n = best.node;
      n;
      n = n->parent)
  {
    ROS_DEBUG("  %.3f %.3f %.3f",
              n->pose.x,
              n->pose.y,
              n->pose.theta);
    if(!n->reading)
    {
      ROS_DEBUG("Reading is NULL");
      continue;
    }
    /*重新计算栅格单元的概率*/
    matcher.invalidateActiveArea();
    matcher.computeActiveArea(smap, n->pose, &((*n->reading)[0]));  
    matcher.registerScan(smap, n->pose, &((*n->reading)[0]));
  }
  /* the map may have expanded, so resize ros message as well */
  if(map_.map.info.width != (unsigned int) smap.getMapSizeX() || map_.map.info.height != (unsigned int) smap.getMapSizeY()) {
    /* NOTE: The results of ScanMatcherMap::getSize() are different from the parameters given to the constructor
       so we must obtain the bounding box in a different way */
    GMapping::Point wmin = smap.map2world(GMapping::IntPoint(0, 0));
    GMapping::Point wmax = smap.map2world(GMapping::IntPoint(smap.getMapSizeX(), smap.getMapSizeY()));
    xmin_ = wmin.x; ymin_ = wmin.y;
    xmax_ = wmax.x; ymax_ = wmax.y;

    ROS_DEBUG("map size is now %dx%d pixels (%f,%f)-(%f, %f)", smap.getMapSizeX(), smap.getMapSizeY(),
              xmin_, ymin_, xmax_, ymax_);
    map_.map.info.width = smap.getMapSizeX();
    map_.map.info.height = smap.getMapSizeY();
    map_.map.info.origin.position.x = xmin_;
    map_.map.info.origin.position.y = ymin_;
    map_.map.data.resize(map_.map.info.width * map_.map.info.height);   //地图需要膨胀
    ROS_DEBUG("map origin: (%f, %f)", map_.map.info.origin.position.x, map_.map.info.origin.position.y);
  }
  /*确定地图的未知区域、自由区域、障碍 */
  for(int x=0; x < smap.getMapSizeX(); x++)   
  {
    for(int y=0; y < smap.getMapSizeY(); y++)
    {
      /// @todo Sort out the unknown vs. free vs. obstacle thresholding
      GMapping::IntPoint p(x, y);
      double occ=smap.cell(p);
      assert(occ <= 1.0);
      if(occ < 0)
        map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = -1;
      else if(occ > occ_thresh_)
      {
        //map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = (int)round(occ*100.0);
        map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 100;
      }
      else
        map_.map.data[MAP_IDX(map_.map.info.width, x, y)] = 0;
    }
  }
  got_map_ = true;
  //make sure to set the header information on the map
  map_.map.header.stamp = ros::Time::now();
  map_.map.header.frame_id = tf_.resolve( map_frame_ );
  sst_.publish(map_.map);
  sstm_.publish(map_.map.info);
}

至此,整个gmapping 的主线已经挑出来了,当然里面还有很多初始化我没讲,而且有很多细节我也还没有弄清楚, 
还有待进一步的研究(比如地图是如何膨胀的,扫描匹配得分计算的具体实施过程)。

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

gmapping 分析 的相关文章

  • 大二上学期数据结构课程设计

    1 报数问题 问题描述 有n个小朋友围成一圈玩游戏 小朋友从1至n编号 2号小朋友坐在1号小朋友的顺时针方向 3号小朋友坐在2号小朋友的顺时针方向 1号小朋友坐在n号小朋友的顺时针方向 游戏开始 从1号小朋友开始顺时针报数 接下来每个小朋友
  • 安装TensorFlow遇到no module named ‘tensorflow’问题解决方法

    按照这个博客https blog csdn net qq 16633405 article details 79941696里的步骤安装TensorFlow时遇到no module named tensorflow 虽然作者给出了一个解决方
  • 文本多分类之Doc2Vec实战篇

    本文链接 https blog csdn net weixin 42608414 article details 88391760 版权 在我之前的几篇博客中 我介绍了两种文档向量化的表示方法 如Sklearn的CountVectorize
  • 1.3. 分治法—最近点对问题

    1 问题描述 给定平面S上n个点 找其中的一对点 使得在n个点组成的所有点对中 该点对间的距离最小 2 求解过程 划分 将集合S分成两个大小基本相等的子集 S 1 S 1 S1 和 S
  • linux 基础知识考试试题,Linux常识型试题

    Linux常识型试题 发布时间 2011 06 06 18 11 10来源 红联作者 lijiang i s 本帖最后由 lijiang 于 2011 10 22 17 51 编辑 i 一 填空题 1 链接分为 和 2 安装Linux系统对
  • 解决Linux界面显示问号字符?与Failed to set locale, defaulting to C报错

    解决方法 暂时性处理 export LC ALL zh CN UTF 8 一劳永逸 vim etc bashrc 然后在最后一行写入 export LC ALL zh CN UTF 8 问题复现 解析 当输入 locale 会得到如下结果
  • 数据结构----利用栈实现表达式的计算

    利用栈实现表达式的计算 例如 12 5 6 9 7 8 5 6 8 5 6 12 要解决的问题主要有两个 和 的运算顺序的处理问题 括号内的表达式优先运算问题 这里利用栈来解决这两个问题 首先我们设置两个栈 一个符号栈 一个数字栈 下面我们
  • Novell数据备份

    从昨天下午到现在 才搞定 关总不提示的情况下 我一直认为xvRf是更新备份数据 cvRf是全部备份 其实则不然 关总告诉我 xvRf是导入数据 而cvRf才是备份数据 如果网络成功链接的话 那NDS服务器的数据就会被老数据覆盖了 幸好幸好
  • Android Studio day_01 初识线性布局和相对布局还有按钮

    序章 今天学习了线性布局 LinearLayout 和相对布局 RelativeLayout 还有Button按钮 布局是要用和进行结束的 至于Botton按钮嘛 使用 gt 结束就好啦 相对布局 RelativeLayout 相对布局我理
  • 卸载npm和安装npm_使用`npm uninstall`卸载npm软件包

    卸载npm和安装npm To uninstall a package you have previously installed locally using npm install
  • 激光雷达对植被冠层结构和SIF同时探测展望

    前言 陆表植被在全球碳循环中起着不可替代的作用 但现阶段 人们对气候变化与植被生态理化功能的关系的研究还不够完善 为了提高气候预测以及缓解气候恶化的速率 对植被参数比如 叶面积指数 leaf 植被冠层结构 canopy 和生态系统以及区域尺
  • Linux服务器程序规范

    Linux服务器程序规范 Linux服务器程序一般都是以后台进程形式运行 后台进程又称为守护进程 daemon 其没有控制终端 不会意外接收到用户输入 守护进程的父进程通常是init进程 PID为1的进程 Linux服务器程序通常有一套日志
  • Tomcat启动不了报 java.net.BindException “Address already in use: NET_Bind“这个异常

    Tomcat在IDEA运行报以下错误 启动不了Tomcat Error running Tomcat 8 5 57开关 Unable to open debugger port 127 0 0 1 63840 java net BindEx
  • Hive文件格式

    文章目录 1 概述 1 1 行存储 列存储 2 TEXTFILE 3 SEQUENCEFILE 3 RCFILE 4 ORCFILE 5 Parquet 8 区别 8 1 空间对比 磁盘空间占用大小比较 8 2 查询语句运行时间大小比较 9
  • socket链接检测超时时间过短导致的问题

    新增了另外一个区域的代理 跨州 原来的代理可达性检测只有50ms 就不够了 导致大量报错 更换为1000毫秒后 就正常了 需要注意网络中几个连接超时时间的设置问题 1 链接超时时间 一般是1 5秒 全内网服务器 可以设置得更短一些 2 等待
  • 《消息队列高手课》 消息积压了该如何处理?

    据我了解 在使用消息队列遇到的问题中 消息积压这个问题 应该是最常遇到的问题了 并且 这个问题还不太好解决 我们都知道 消息积压的直接原因 一定是系统中的某个部分出现了性能问题 来不及处理上游发送的消息 才会导致消息积压 所以 我们先来分析
  • CSS背景属性Background详解

    本文详解了CSS的背景属性Background 包括CSS3中新增的背景属性 如果你是个CSS初学者 还可以查看之前介绍的CSS浮动属性和CSS透明属性详解 css2 中的背景 background CSS2 中有5个主要的背景 backg
  • Maven详解之仓库------本地仓库、远程仓库

    Dragon s Life 坚持 完成每一个目标 目录视图 摘要视图 订阅 征文 从高考 到程序员 深度学习与TensorFlow入门一课搞定 每周荐书 Web扫描 HTML 5 Python 评论送书 Maven详解之仓库 本地仓库 远程
  • Python+Selenium-5-driver.page_source获取页面源码

    driver page source selenium的page source方法可以获取到页面源码 跟爬虫有点相似 获取到页面资源 提取出我们需要的信息 案例 以煎蛋网为例 获取首页的全部title 获取页面源码 使用re正则提取需要的t

随机推荐

  • SpringBoot自定义工厂类读取yml配置文件&&SpringBoot轻松读取properties文件

    PropertySource指定文件地址 ConfigurationProperties指定前缀 第一次 SpringBoot 读取配置文件 demo如下 designers yml文件 designer owner openids 8hV
  • IDEA导入lib目录下的jar包

    https blog csdn net u010286027 article details 85248719 ops request misc request id biz id 102 utm term idea E6 96 B0 E5
  • LeetCode【114】二叉树展开为链表

    题目 给定一个二叉树 原地将它展开为链表 例如 给定二叉树 将其展开为 最终转化完 pre节点只有right 没有left TreeNode pre null public void flatten TreeNode root if roo
  • 【Mariadb高可用MHA】

    目录 一 概述 1 概念 2 组成 3 特点 4 工作原理 二 案例介绍 1 192 168 42 3 2 192 168 42 4 3 192 168 42 5 4 192 168 42 6 三 实际构建MHA 1 ssh免密登录 1 1
  • openshift搭建Istio

    本文档覆盖了官方文档的Setup的所有章节 一 安装Istio 本次安装的Istio版本为1 7 0 环境为openshift 4 3 注 不建议使用openshift 1 11 即kubernetes 3 11 安装istio 可能会出现
  • HBase简介(很好的梳理资料)

    http jiajun iteye com blog 899632 一 简介 history started by chad walters and jim 2006 11 G release paper on BigTable 2007
  • 腾讯云如何修改域名DNS服务器

    当你在腾讯云购买域名后 如果 DNS 服务器不正确 要把域名 DNS 修改为提示的 DNS 地址 解析后才生效 下面老魏说下操作步骤 一 通过以下步骤查看 DNS 服务器是否正确 登录腾讯云控制台 选择 云产品 gt 域名与网站 gt 云解
  • 短视频seo矩阵系统源码开发与部署全解析

    在这个数字化快速发展的时代 短视频已经成为人们获取娱乐 学习 商业信息的主要途径之一 对于企业来说 利用短视频矩阵进行高效且精准的营销推广 无疑是一个重要的战略方向 本文将详细介绍如何进行短视频矩阵源码的开发与部署 一 开发篇 短视频矩阵源
  • linux 常用语句 grep、awk、sed

    复习资料 一 find grep 管道符 1 find 路径 name 文件名 查找文件 2 grep sex true 文本包含sex true 的行显示出来 3 grep sex true grep o age 18 对grep sex
  • 【Kettle】将【MySQL表按字段同步、更新】【脚本运行】

    前提数据 转换 1 表输入设置 2 插入 更新设置 作业 模块设置 SQL设置 手动输入脚本内容 每次运行都会运行此脚本
  • 十、工业相机与SCARA机械臂的坐标系标定

    注 感谢固高长江研究院徐工程师的技术讲解 以及matlab程序 机器人系统程序的提供 在工业现场当中 相机拍摄到的图像有一个相机坐标系 而机器人自身也有一个机器人自身的坐标系 两者互相独立 当我们通过相机进行对物体进行拍摄 通过模式识别得到
  • pygame 学习记录

    话不多说上代码 import pygame import sys pygame init size width height 900 700 speed 2 1 bg 255 255 255 RGB screen pygame displa
  • 文件上传的各种绕过方式

    1 前端绕过 更改前端的过滤方法进行绕过 1 通过浏览器插件来删除检查后援js代码 然后上传webshell 2 上传文件时把后缀名改成png格式 上传时在通过抓包工具把后缀名改回来 3 更改Content Tybe为image jpeg
  • C#连接sqlServer数据库详解

    C 是如何跟SQL Server进行连接的 在C NET程序设计中 离不开ADO NET ADO NET是 NET连接数据库的重要组件 使用其可以很方便地访问数据库 ADO NET还可以访问Oracle数据库 Access数据库 SQL S
  • Echarts dataZoom x轴横坐标缩放

    https echarts apache org zh option html dataZoom Echarts dataZoom x轴横坐标缩放 把 dataZoom 房子 option下的第一级 和 xAxis yAxis series
  • SpringBoot 启动成功监听

    CommandLineRunner 接口 启动成功后的回调 接口代码 package org springframework boot FunctionalInterface public interface CommandLineRunn
  • MySQL优化(二):MySQL 索引深入解读

    目录 一 索引是什么 1 索引定义 2 索引类型 3 索引的创建 4 索引的删除 二 索引存储模型 2 1 二分查找 2 2 二叉查找树 2 3 平衡二叉树 2 4 多路平衡查找树 B Tree 2 5 加强版多路平衡查找树 B Tree
  • 【统计模拟及其R实现】分层抽样法 / 条件期望法 习题答案(超详细)

    课本 统计模拟及其R实现 肖枝红 朱强 武汉大学出版社 参考资料 方差缩减技术 条件期望法 目录 1 分层抽样法 2 条件期望法 1 分层抽样法 题目1 如何通过分层抽样法得到
  • [人工智能-深度学习-51]:循环神经网络 - RNN基本原理详解

    作者主页 文火冰糖的硅基工坊 文火冰糖 王文兵 的博客 文火冰糖的硅基工坊 CSDN博客 本文网址 https blog csdn net HiWangWenBing article details 121387285 目录 第1章 详解前
  • gmapping 分析

    转载 这一篇先讲我对gmapping源码的理解 难免有错 欢迎指正 相互学习 原博客 https blog csdn net roadseek zw article details 53316177 博客主页 https blog csdn