1.karto-slam涉及的类-雷达以及雷达数据相关

2023-05-16

首先是最简单的

1. sensor_msgs::LaserScan, 主要包括header、还有激光参数(扫射范围距离,步长,时间等,不包含位姿信息,header里面含有frame_id)。

typedef ::sensor_msgs::LaserScan_<std::allocator<void> > LaserScan;
struct LaserScan_
{
  typedef LaserScan_<ContainerAllocator> Type;

  LaserScan_()
    : header()
    , angle_min(0.0)
    , angle_max(0.0)
    , angle_increment(0.0)
    , time_increment(0.0)
    , scan_time(0.0)
    , range_min(0.0)
    , range_max(0.0)
    , ranges()
    , intensities()  {
    }
  LaserScan_(const ContainerAllocator& _alloc)
    : header(_alloc)
    , angle_min(0.0)
    , angle_max(0.0)
    , angle_increment(0.0)
    , time_increment(0.0)
    , scan_time(0.0)
    , range_min(0.0)
    , range_max(0.0)
    , ranges(_alloc)
    , intensities(_alloc)  {
  (void)_alloc;
    }



   typedef  ::std_msgs::Header_<ContainerAllocator>  _header_type;
  _header_type header;

   typedef float _angle_min_type;
  _angle_min_type angle_min;

   typedef float _angle_max_type;
  _angle_max_type angle_max;

   typedef float _angle_increment_type;
  _angle_increment_type angle_increment;

   typedef float _time_increment_type;
  _time_increment_type time_increment;

   typedef float _scan_time_type;
  _scan_time_type scan_time;

   typedef float _range_min_type;
  _range_min_type range_min;

   typedef float _range_max_type;
  _range_max_type range_max;

   typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other >  _ranges_type;
  _ranges_type ranges;

   typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other >  _intensities_type;
  _intensities_type intensities;





  typedef boost::shared_ptr< ::sensor_msgs::LaserScan_<ContainerAllocator> > Ptr;
  typedef boost::shared_ptr< ::sensor_msgs::LaserScan_<ContainerAllocator> const> ConstPtr;

}; // struct LaserScan_

2. 算法根据scan的ranges得到了range_scan,这个是

  class LocalizedRangeScan : public LaserRangeScan

先看 LaserRangeScan

主要有两个参数:储存range readings的 成员参数,记录上个参数的size的 成员参数。

其他就是一些得到参数,设置参数的成员函数。

  /**
   * LaserRangeScan representing the range readings from a laser range finder sensor.
   */
  class LaserRangeScan : public SensorData
  {
  public:
    // @cond EXCLUDE
    KARTO_Object(LaserRangeScan)
    // @endcond

  public:
    /**
     * Constructs a scan from the given sensor with the given readings
     * @param rSensorName
     */
    LaserRangeScan(const Name& rSensorName)
      : SensorData(rSensorName)
      , m_pRangeReadings(NULL)
      , m_NumberOfRangeReadings(0)
    {
    }

    /**
     * Constructs a scan from the given sensor with the given readings
     * @param rSensorName
     * @param rRangeReadings
     */
    LaserRangeScan(const Name& rSensorName, const RangeReadingsVector& rRangeReadings)
      : SensorData(rSensorName)
      , m_pRangeReadings(NULL)
      , m_NumberOfRangeReadings(0)
    {
      assert(rSensorName.ToString() != "");

      SetRangeReadings(rRangeReadings);
    }

    /**
     * Destructor
     */
    virtual ~LaserRangeScan()
    {
      delete [] m_pRangeReadings;
    }

  public:
    /**
     * Gets the range readings of this scan
     * @return range readings of this scan
     */
    inline kt_double* GetRangeReadings() const
    {
      return m_pRangeReadings;
    }

    inline RangeReadingsVector GetRangeReadingsVector() const
    {
      return RangeReadingsVector(m_pRangeReadings, m_pRangeReadings + m_NumberOfRangeReadings);
    }

    /**
     * Sets the range readings for this scan
     * @param rRangeReadings
     */
    inline void SetRangeReadings(const RangeReadingsVector& rRangeReadings)
    {
      // ignore for now! XXXMAE BUGUBUG 05/21/2010 << TODO(lucbettaieb): What the heck is this??
      // if (rRangeReadings.size() != GetNumberOfRangeReadings())
      // {
      //   std::stringstream error;
      //   error << "Given number of readings (" << rRangeReadings.size()
      //         << ") does not match expected number of range finder (" << GetNumberOfRangeReadings() << ")";
      //   throw Exception(error.str());
      // }

      if (!rRangeReadings.empty())
      {
        if (rRangeReadings.size() != m_NumberOfRangeReadings)
        {
          // delete old readings
          delete [] m_pRangeReadings;

          // store size of array!
          m_NumberOfRangeReadings = static_cast<kt_int32u>(rRangeReadings.size());

          // allocate range readings
          m_pRangeReadings = new kt_double[m_NumberOfRangeReadings];
        }

        // copy readings
        kt_int32u index = 0;
        const_forEach(RangeReadingsVector, &rRangeReadings)
        {
          m_pRangeReadings[index++] = *iter;
        }
      }
      else
      {
        delete [] m_pRangeReadings;
        m_pRangeReadings = NULL;
      }
    }

    /**
     * Gets the laser range finder sensor that generated this scan
     * @return laser range finder sensor of this scan
     */
    inline LaserRangeFinder* GetLaserRangeFinder() const
    {
      return SensorManager::GetInstance()->GetSensorByName<LaserRangeFinder>(GetSensorName());
    }

    /**
     * Gets the number of range readings
     * @return number of range readings
     */
    inline kt_int32u GetNumberOfRangeReadings() const
    {
      return m_NumberOfRangeReadings;
    }

  private:
    LaserRangeScan(const LaserRangeScan&);
    const LaserRangeScan& operator=(const LaserRangeScan&);

  private:
    kt_double* m_pRangeReadings;
    kt_int32u m_NumberOfRangeReadings;
  };  // LaserRangeScan

上面两个参数:

一帧scan的所有距离值,指向数组的指针
一帧scan的点数,也就是数组的个数

3. 然后是LocalizedRangeScan

  /**
   * The LocalizedRangeScan contains range data from a single sweep of a laser range finder sensor
   * in a two-dimensional space and position information. The odometer position is the position
   * reported by the robot when the range data was recorded. The corrected position is the position
   * calculated by the mapper (or localizer)
   */
  class LocalizedRangeScan : public LaserRangeScan

储存的是激光数据、里程计表储存的是记录激光数据时机器人的位姿、矫正后的正确位姿记录的由mapper计算出的对应的位置。

主要参数包括,odom坐标下的机器人位置,mapper得到的机器人pose,readings中心pose,世界坐标系下的readings,过滤之前的readings,帧雷达数据的边框。

    /**
     * Odometric pose of robot
     */
    Pose2 m_OdometricPose;

    /**
     * Corrected pose of robot calculated by mapper (or localizer)
     */
    Pose2 m_CorrectedPose;

  protected:
    /**
     * Average of all the point readings
     * 所有point的readings的平均值,中心位置的点
     */
    Pose2 m_BarycenterPose;

    /**
     * Vector of point readings
     * 这里存储了将激光数据转换为在世界坐标下的二维坐标结果,在update函数实现。
     */
    PointVectorDouble m_PointReadings;

    /**
     * Vector of unfiltered point readings
     * 过滤之前的集合
     */
    PointVectorDouble m_UnfilteredPointReadings;

    /**
     * Bounding box of localized range scan
     * Bounding box:障碍物的边框???
     * 这帧雷达数据的边框
     */
    BoundingBox2 m_BoundingBox;

    /**
     * Internal flag used to update point readings, barycenter and bounding box
     */
    kt_bool m_IsDirty;

主要成员函数,可以实现设置这一帧对应的里程计位姿,更正后的里程计姿态(后面运行程序看看在哪个坐标系下),计算point readings' center, 计算传感器位置(相对于机器人的位置偏置已知)相关。比较重要的包括:

1. 得到这一帧的边框:

   /**
     * Gets the bounding box of this scan
     * @return bounding box of this scan
     */
    inline const BoundingBox2& GetBoundingBox() const

2. 得到在地图坐标下的point readings 这里其实就是返回的m_pointreadings 参数,

别的函数里看的觉得point readings是

在odom

或者mapper计算下的坐标系,

或者是在世界坐标系下的二维坐标结果,

还没有一个统一的认识。(后续更新,应该是map或世界坐标系,由mapper或者定位模块计算的)

    /**
     * Get point readings in local coordinates
     */
    inline const PointVectorDouble& GetPointReadings(kt_bool wantFiltered = false) const

3. 更新函数主要是计算point readings,以及计算这一帧的boundingBox

    /**
     * Compute point readings based on range readings
     * Only range readings within [minimum range; range threshold] are returned
     */
    virtual void Update()
    {
      LaserRangeFinder* pLaserRangeFinder = GetLaserRangeFinder(); //得到生成这一帧的激光雷达装置

      if (pLaserRangeFinder != NULL)
      {
        m_PointReadings.clear(); //激光数据转化为在世界坐标下的二维坐标结果
        m_UnfilteredPointReadings.clear();

        kt_double rangeThreshold = pLaserRangeFinder->GetRangeThreshold();
        kt_double minimumAngle = pLaserRangeFinder->GetMinimumAngle();
        kt_double angularResolution = pLaserRangeFinder->GetAngularResolution();
        Pose2 scanPose = GetSensorPose(); //得到传感器的位置 , 目前认为是在odom坐标系下表示

        // compute point readings
        Vector2<kt_double> rangePointsSum; // 点readings的和, 在real space 下的 x y
        kt_int32u beamNum = 0;
        for (kt_int32u i = 0; i < pLaserRangeFinder->GetNumberOfRangeReadings(); i++, beamNum++)
        {
          kt_double rangeReading = GetRangeReadings()[i]; // 得到一帧的第i个光束
          if (!math::InRange(rangeReading, pLaserRangeFinder->GetMinimumRange(), rangeThreshold))
          {
            kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;

            Vector2<kt_double> point;
            point.SetX(scanPose.GetX() + (rangeReading * cos(angle))); //目前认为是在odom坐标系下表示 计算的到point readings 由rang readings --> point readings 
            point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));

            m_UnfilteredPointReadings.push_back(point);
            continue;
          }

          kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;

          Vector2<kt_double> point;
          point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
          point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));

          m_PointReadings.push_back(point);
          m_UnfilteredPointReadings.push_back(point);

          rangePointsSum += point;
        }

        // compute barycenter
        kt_double nPoints = static_cast<kt_double>(m_PointReadings.size());
        if (nPoints != 0.0)
        {
          Vector2<kt_double> averagePosition = Vector2<kt_double>(rangePointsSum / nPoints);
          m_BarycenterPose = Pose2(averagePosition, 0.0);
        }
        else
        {
          m_BarycenterPose = scanPose;
        }

        // calculate bounding box of scan
        m_BoundingBox = BoundingBox2(); // 默认无参构造函数
        m_BoundingBox.Add(scanPose.GetPosition());
        //得到这一帧的左下角坐标,右上角坐标,也就边框找到了
        forEach(PointVectorDouble, &m_PointReadings)
        {
          m_BoundingBox.Add(*iter);
        }
      }

      m_IsDirty = false;
    }

参考:https://github.com/kadn/open_karto

得出的结论,

  class LaserRangeScan : public SensorData   //这里面存储了最原始的扫描深度数据,然后在LocalizedRangeScan中存储了扫描点在世界坐标系中的位置
    inline Pose2 GetSensorPose() const
    {
      return GetSensorAt(m_CorrectedPose);   //基于修正的robot位置以及之前设定的laser scan相对于 robot的位置来求出laser scan在地图中的位置
    }

m_CorrectedPose 是地图(map、世界)坐标系中的位置, m_Odo.... 是odom坐标系下的

        m_PointReadings.clear(); //激光数据转化为在世界坐标下(map)的二维坐标结果
            point.SetX(scanPose.GetX() + (rangeReading * cos(angle))); //目前认为是在map坐标系下表示 计算的到point readings 由rang readings --> point readings 

代码中的注释:local coordinates指的也是map frame???

rPose1.GetPosition()得到的是pose1的坐标系相对世界坐标系平移,rPose1.GetHeading() 是旋转

附录:调试信息(没有用,不用看)

//---------------------------
Vector2<kt_double> pointmin = m_PointReadings[0];
Vector2<kt_double> pointmax = m_PointReadings[0];
for(int i = 0; i < m_PointReadings.size(); i++)
{
  if(pointmin.GetX() > m_PointReadings[i].GetX() && pointmin.GetY() > m_PointReadings[i].GetY() )
  {
    pointmin.SetX(m_PointReadings[i].GetX());
    pointmin.SetY(m_PointReadings[i].GetY());
  }
  if(pointmax.GetX() < m_PointReadings[i].GetX() && pointmax.GetY() < m_PointReadings[i].GetY() )
  {
    pointmin.SetX(m_PointReadings[i].GetX());
    pointmin.SetY(m_PointReadings[i].GetY());
  }    
}
pointmin.SetX(pointmin.GetX() / 3);
pointmin.SetY(pointmin.GetY() / 3);
m_PointReadings.push_back(pointmin);
pointmax.SetX(pointmax.GetX() * 2);
pointmax.SetY(pointmax.GetY() * 2);
m_PointReadings.push_back(pointmax);
//---------------------------

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

1.karto-slam涉及的类-雷达以及雷达数据相关 的相关文章

随机推荐

  • C++学习笔记

    文章目录 一 基础入门1 常量2 关键字3 数据类型3 1 整型3 2 浮点型3 3 字符型3 4 字符串类型3 5 布尔类型 4 数据的输入与输出5 运算符6 数组6 1 一维数组6 2 二维数组 7 函数8 指针9 结构体 二 核心编程
  • JS实现继承的几种方式

    JS继承的实现方式 堪称最全最详细 前沿看js继承这块时我看的几个教程都是说的很简单或者是没有说全就自行百度看了好多总结了下有 xff1a 1 构造函数继承 2 原型链继承 3 组合继承 4 class继承 5 实例继承 6 拷贝继承 7
  • 51单片机入门之点亮发光二极管

    1 任务书 用51单片机控制一个发光二极管 xff0c 打开单片机后LED亮 2 分析 首先是考虑电路连接问题 单片机所有1 O 口都可以驱动发光二极管 设选用P2 0 来接发光二极管 xff0c 所谓 闪亮 xff0c 就是点亮发光管后
  • 51单片机入门之开关控制

    1 任务书 使用拨扭开关控制led xff0c 用微动开关控制led 2 分析 拨钮开关无非就是 打开 跟 关闭 两个状态 xff0c 也就是0跟1 xff0c 打开无非就是接通关闭无非就是断开 那我们应该怎么接入单片机了 xff0c 其实
  • 51单片机静态动态数码管显示

    51单片机静态动态数码管显示 通过此实训了解动态数码管的显示原理 xff0c 掌握编码方法 共阴极和其阴极数码管的不同之处及常用设计方法 实训设备 这里使用的377锁存器模块控制的数码管下面就是电路图 显示内容 在显示模块的八位 LED 数
  • 51单片机矩阵键盘控制数码管

    51单片机矩阵键盘控制数码管 我们先了解矩阵键盘的工作原理 xff0c 掌握编码方法并能够编写出扫描程序 xff0c 使用矩阵键盘控制数码管输出矩阵键值 显示内容 在显示模块的八位 LED 数码的个位显示当前使用矩阵键盘所按下的值 键阵键盘
  • 51单片机继电器控制直流电机正反转

    51单片机继电器控制直流电机正反转 用继电器控制 24V 直流电机的转动与停止 继电器是常用的电气隔离器件 简单的驱动电路是用三极管直接驱动 该电路驱动简单 成本低廉 当控制电路为高电平时 xff0c NPN 型三极管就会饱和导通 xff0
  • 51单片机定时器流水灯控制

    51单片机定时器控制led流水灯数码管进行计数 51单片机根据不同的型号有不同数量的定时器的 xff0c 而这些定时器的大概用法是差不多的我们今天就使用定时器来控制led流水灯 实训要求 使用单片机定时器对led灯进行控制 xff0c 数码
  • esp8266单片机使用MAX7219芯片驱动点阵屏幕

    esp8266单片机使用MAX7219芯片驱动点阵屏幕 我们这里使用的单片机是一块esp8266 xff0c 点阵屏幕的话就是买的普通16脚红色的 xff0c 驱动芯片就是MAX7219芯片 xff0c 只需要依次把芯片的clk xff0c
  • 使用自己开发的app远程控制MAX7219点阵屏幕

    使用自己开发的app远程控制MAX7219点阵屏幕 一 功能介绍 xff1a 二 芯片介绍 xff1a 三 实现原理 xff1a 四 代码部分 xff1a 其它资料 xff1a 一 功能介绍 xff1a 1 可以固定显示想显示的内容 2 点
  • go发送http请求

    说明 xff1a 写项目时候用到的 xff0c go发送http请求用到的一个方法 span class token keyword func span 函数名 span class token punctuation span body
  • js事件流

    事件流指的是事件完整执行过程中的流动路径 事件流分为捕获阶段和冒泡阶段 捕获阶段是从父到子 xff1b 冒泡阶段是从子到父 事件冒泡 xff1a 事件冒泡概念 xff1a 当一个元素的事件被触发的时候 xff0c 同样的事件将会在该元素的祖
  • 树莓派安装python3.7.3

    一 安装依赖包 sudo apt get install y make build essential libssl dev zlib1g dev sudo apt get install y libbz2 dev libreadline
  • vscode中调试webpack构建的项目

    在webpack的配置中 xff1a devtool span class token punctuation span span class token string 39 source map 39 span span class to
  • mac下proxychains4的配置文件位置

    mac下proxychains4的配置文件位置 xff1a usr local etc proxychains conf span class token function vim span usr local etc proxychain
  • 1. 驱动开发--基础知识

    文章目录 1 驱动的概念2 linux体系架构3 模块化设计3 1 微内核和宏内核 4 linux设备驱动分类4 1 驱动分类4 2 三类驱动程序详细对比分析4 3 为什么字符设备驱动最重要 5 驱动程序的安全性要求5 1 驱动是内核的一部
  • 【论文笔记】Ensemble Augmented-Shot Y-shaped Learning

    论文笔记 EASY Ensemble Augmented Shot Y shaped Learning State Of The Art Few Shot Classification with Simple Ingredients Int
  • Ubuntu下的文件保存及退出

    这篇文章是写给我自己的 xff0c 怕自己以后忘了 我很多时候会在ubuntu下发现键盘并不那么好使 输入 vim test cpp 然后输入i o a xff0c 输入以上三种 xff0c 进入编辑状态 输入完成 xff0c 按esc退出
  • 机会总是留给有准备的人

    qqq
  • 1.karto-slam涉及的类-雷达以及雷达数据相关

    首先是最简单的 1 sensor msgs LaserScan 主要包括header 还有激光参数 xff08 扫射范围距离 xff0c 步长 xff0c 时间等 xff0c 不包含位姿信息 xff0c header里面含有frame id