ESVO2代码详解

写在前面的:详细阅读事件-惯性SLAM开源框架ESVO2代码,解释代码逻辑和核心功能。另外,感谢作者的开源工作!

相关工作

[1] ESVO2: Direct Visual-Inertial Odometry with Stereo Event Cameras, Junkai Niu, Sheng Zhong, Xiuyuan Lu, Shaojie Shen, Guillermo Gallego, Yi Zhou, arxiv. PDF.

[2] IMU-Aided Event-based Stereo Visual Odometry, Junkai Niu, Sheng Zhong, Yi Zhou, ICRA 2024. PDF.

[3] Event-based Stereo Visual Odometry, Yi Zhou, Guillermo Gallego, Shaojie Shen, IEEE Transactions on Robotics (T-RO), 37(5):1433-1450, 2021. Project page, PDF.

[4] Semi-dense 3D Reconstruction with a Stereo Event Camera, Yi Zhou, Guillermo Gallego, Henri Rebecq, Laurent Kneip, Hongdong Li, Davide Scaramuzza, ECCV 2018. PDF.

整体逻辑:


🌞ImageRepresentation 节点

⚡Structure

1.构造函数ImageRepresentation::ImageRepresentatio:

/**
   * todo:构造函数:初始化ImageRepresentation类
   * @param nh ROS节点句柄
   * @param nh_private ROS私有节点句柄
   * 功能:
   * 1. 设置ROS话题订阅和发布
   * 2. 加载参数配置
   * 3. 启动图像生成线程
   */
  ImageRepresentation::ImageRepresentation(ros::NodeHandle &nh, ros::NodeHandle nh_private) : nh_(nh)

2.析构函数ImageRepresentation::~ImageRepresentation

3.类初始化函数ImageRepresentation::init(int width, int height):

/**
   * todo:类初始化函数
   * @param width 图像宽度
   * @param height 图像高度
   * 功能:
   * 1. 初始化传感器尺寸
   * 2. 初始化图像表示矩阵
   * 3. 预分配事件向量内存
   */
  void ImageRepresentation::init(int width, int height)

4.图像生成主循环ImageRepresentation::GenerationLoop:

/**
  * todo:图像生成主循环
  * 功能:
  * 1. 按指定频率生成图像表示
  * 2. 调用createImageRepresentationAtTime处理事件
  */
  void ImageRepresentation::GenerationLoop()

5.自适应累积(AA)处理线程ImageRepresentation::AA_thread:

/**
   * todo:自适应累积(AA)处理线程
   * @param ptr_e 事件迭代器
   * @param distance 处理的事件距离
   * @param external_t 外部时间
   * 功能:
   * 1. 实现自适应累积算法
   * 2. 生成AA图像表示
   * 3. 发布AA相关图像
   */
  void ImageRepresentation::AA_thread(std::vector<dvs_msgs::Event>::iterator &ptr_e, int distance, double external_t)

6.在指定时间点创建图像表示ImageRepresentation::createImageRepresentationAtTime:

/**
   * todo:在指定时间点创建图像表示
   * @param external_sync_time 外部同步时间
   * 功能:
   * 1. 生成时间表面(TS)表示
   * 2. 生成累积帧(AA)表示
   * 3. 处理图像畸变校正
   * 4. 发布各种图像表示
   */
  void ImageRepresentation::createImageRepresentationAtTime(const ros::Time &external_sync_time)

7.清理指定距离内的事件函数ImageRepresentation::clearEvents

8.事件回调函数ImageRepresentation::eventsCallback:

/**
  * todo:事件回调函数
  * @param msg 事件数组消息
  * 功能:
  * 1. 接收和处理新的事件
  * 2. 维护事件队列
  * 3. 触发图像生成
  */
  void ImageRepresentation::eventsCallback(const dvs_msgs::EventArray::ConstPtr &msg)

9.清空事件队列,释放内存函数ImageRepresentation::clearEventQueue

10.Sobel边缘检测处理函数ImageRepresentation::sobel

11.加载相机标定信息函数ImageRepresentation::loadCalibInfo:

 /**
   * todo:加载相机标定信息
   * @param cameraSystemDir 标定文件目录
   * @param is_left 是否为左相机
   * @return 加载是否成功
   * 功能:
   * 1. 从YAML文件加载相机参数
   * 2. 计算去畸变映射
   * 3. 预计算校正查找表
   */
  bool ImageRepresentation::loadCalibInfo(const std::string &cameraSystemDir, bool &is_left)

12.检查文件是否存在函数ImageRepresentation::fileExists

✨ 1. 头文件ImageeRepresentation.h:

#ifndef image_representation_H_
#define image_representation_H_

#include <ros/ros.h>
#include <std_msgs/Time.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/image_encodings.h>
#include <dynamic_reconfigure/server.h>
#include <image_transport/image_transport.h>
#include <image_representation/TicToc.h>

#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>

#include <dvs_msgs/Event.h>
#include <dvs_msgs/EventArray.h>

#include <deque>
#include <mutex>
#include <Eigen/Eigen>
#include <vector>
#include <algorithm>
#include <thread>

#include <yaml-cpp/yaml.h>

namespace image_representation
{
    // 定义全局事件队列,使用map存储,key为时间戳,value为事件数据
  using EventQueue = std::deque<dvs_msgs::Event>;

    // 定义时间比较结构体,用于map排序
  struct ROSTimeCmp
  {
    bool operator()(const ros::Time &a, const ros::Time &b) const
    {
      return a.toNSec() < b.toNSec();  // 按纳秒级时间戳比较
    }
  };

    // 定义全局事件队列,使用map存储,key为时间戳,value为事件数据
  using GlobalEventQueue = std::map<ros::Time, dvs_msgs::Event, ROSTimeCmp>;

    // 在事件队列中找到第一个时间戳不小于给定时间t的事件位置
  inline static EventQueue::iterator EventBuffer_lower_bound(
      EventQueue &eb, ros::Time &t)
  {
    return std::lower_bound(eb.begin(), eb.end(), t,
                            [](const dvs_msgs::Event &e, const ros::Time &t)
                            { return e.ts.toSec() < t.toSec(); });
  }

    // 在事件队列中找到第一个时间戳大于给定时间t的事件位置
  inline static EventQueue::iterator EventBuffer_upper_bound(
      EventQueue &eb, ros::Time &t)
  {
    return std::upper_bound(eb.begin(), eb.end(), t,
                            [](const ros::Time &t, const dvs_msgs::Event &e)
                            { return t.toSec() < e.ts.toSec(); });
  }

    // 在事件向量中找到第一个时间戳不小于给定时间t的事件位置
  inline static std::vector<dvs_msgs::Event>::iterator EventVector_lower_bound(
      std::vector<dvs_msgs::Event> &ev, double &t)
  {
    return std::lower_bound(ev.begin(), ev.end(), t,
                            [](const dvs_msgs::Event &e, const double &t)
                            { return e.ts.toSec() < t; });
  }

  class ImageRepresentation
  {
  public:
    ImageRepresentation(ros::NodeHandle &nh, ros::NodeHandle nh_private);
    virtual ~ImageRepresentation();

    // 时间比较静态方法
    static bool compare_time(const dvs_msgs::Event &e, const double reference_time)
    {
      return reference_time < e.ts.toSec();
    }

  private:
    ros::NodeHandle nh_;
    // core 初始化图像表示系统,设置图像尺寸和相关数据结构
    void init(int width, int height);

    // 在指定时间点创建事件图像表示 Support: TS, AA, negative_TS, negative_TS_dx, negative_TS_dy
    void createImageRepresentationAtTime(const ros::Time &external_sync_time);

    // 图像生成的主循环函数,持续处理事件并生成不同类型的图像表示
    void GenerationLoop();

    // callbacks 事件回调函数,处理接收到的事件数组
    void eventsCallback(const dvs_msgs::EventArray::ConstPtr &msg);

    // utils 清空事件队列,释放内存
    void clearEventQueue();
    // 加载相机标定信息 is_left: 是否为左相机 返回: 加载是否成功
    bool loadCalibInfo(const std::string &cameraSystemDir, bool &is_left);
    // 清理指定距离内的事件
    void clearEvents(int distance, std::vector<dvs_msgs::Event>::iterator ptr_e);

    // AA(Adaptive Accumulation)处理线程
    void AA_thread(std::vector<dvs_msgs::Event>::iterator &ptr_e, int distance, double external_t);
    // Sobel边缘检测处理函数
    void sobel(double external_t);
    // 检查文件是否存在
    bool fileExists(const std::string &filename);
    // tests

    // calibration parameters
    cv::Mat camera_matrix_, dist_coeffs_;
    cv::Mat rectification_matrix_, projection_matrix_;
    std::string distortion_model_; // 畸变模型类型
    cv::Mat undistort_map1_, undistort_map2_;
    Eigen::Matrix2Xd precomputed_rectified_points_; // 预计算的校正点

      // sub & pub
    ros::Subscriber event_sub_;
    ros::Subscriber camera_info_sub_;

    image_transport::Publisher dx_image_pub_, dy_image_pub_; // 梯度图像发布器
    image_transport::Publisher image_representation_pub_TS_;
    image_transport::Publisher image_representation_pub_negative_TS_; // 负时间表面发布器
    image_transport::Publisher image_representation_pub_AA_frequency_; // AA频率图发布器
    image_transport::Publisher image_representation_pub_AA_mat_; // AA矩阵发布器

    bool left_;
    cv::Mat negative_TS_img;
    cv_bridge::CvImage cv_dx_image, cv_dy_image;
    std::thread thread_sobel;

    // online parameters
    bool bCamInfoAvailable_;// 相机信息是否可用
    bool bUse_Sim_Time_;        // 是否使用仿真时间
    cv::Size sensor_size_;      // 传感器尺寸
    ros::Time sync_time_;       // 同步时间
    bool bSensorInitialized_;   // 传感器是否初始化


      // offline parameters TODO
    double decay_ms_;           // 衰减时间(毫秒)
    bool ignore_polarity_;      // 是否忽略极性
    int median_blur_kernel_size_;  // 中值滤波核大小
    int blur_size_;             // 模糊核大小
    int max_event_queue_length_;   // 最大事件队列长度
    int events_maintained_size_;    // 维护的事件数量

    // containers
    EventQueue events_;         // 事件队列
    std::vector<dvs_msgs::Event> vEvents_;  // 事件向量
    cv::Mat representation_TS_;   // 时间表面表示
    cv::Mat representation_AA_;   // AA表示
    Eigen::MatrixXd TS_temp_map;  // 临时时间表面映射

    // for rectify
    cv::Mat undistmap1_, undistmap2_;
    bool is_left_, bcreat_;

    // thread mutex
    std::mutex data_mutex_; // 数据互斥锁

    enum RepresentationMode
    {
      Linear_TS, // 0
      AA2,       // 1
      Fast       // 2
    } representation_mode_;

    // parameters
    bool bUseStereoCam_;
    double decay_sec_; // TS param
    int generation_rate_hz_;
    int x_patches_, y_patches_;
    // std::vector<dvs_msgs::Event>::iterator ptr_e_;

    // calib info
    std::string calibInfoDir_;
    std::vector<cv::Point> trapezoid_;
  };
} // namespace image_representation
#endif // image_representation_H_

✨2. 核心功能——生成时间表面TimeSurface以及自适应累积图AA map

函数:void ImageRepresentation::createImageRepresentationAtTime(const ros::Time &external_sync_time)

TimeSureface(TS)的数学原理:由于event是一个串行异步数据流,所以期望能够对其进行类似于图像的表征,以服务于后续的位姿估计。

TS是一种2D图像表示,其中每个像素存储一个时间值,计算公式为:

$$\mathcal{T}(\mathbf{x},t) = \exp\left(-\frac{t-t_{\text{last}}(\mathbf{x})}{\eta}\right)$$

时间表面函数$\mathcal{T}(\mathbf{x},t)$中,$\mathbf{x} = (u,v)$表示像素坐标,$t$代表当前时间,$t_{\text{last}}(\mathbf{x})$表示在该像素位置最后一个事件的时间戳,$\eta$是衰减率参数(通常设置为30ms)。该函数的值域为[0,1],在实际可视化时会被缩放到[0,255]的范围内。

TS生成核心代码:

    // 4.1 启动AA处理线程
std::thread thread0(&ImageRepresentation::AA_thread, this, std::ref(ptr_e), distance, external_t);
	// 4.2 生成TS(时间表面)
representation_TS_.setTo(cv::Scalar(0));
cv::Mat TS_img = cv::Mat::zeros(sensor_size_, CV_64F);

// if the event rate is too high, we need to downsample the events
// step = 1 indicates that we use all the events
// double step = static_cast<double>(distance) / 90000.0;

double step = 1;
std::vector<dvs_msgs::Event>::iterator it = vEvents_.begin();

   // 4.3 生成时间表面映射 更新每个像素的最新事件时间
for (int i = 0; i < distance; i++)
{
	int index = static_cast<int>(i * step);
	if (index > distance - 2)
	break;
	dvs_msgs::Event e = *(it + index);
	TS_temp_map(e.y, e.x) = e.ts.toSec() / decay_sec_; // 归一化时间戳
}

	// 4.4 时间表面计算
cv::eigen2cv(TS_temp_map, representation_TS_);
representation_TS_ = representation_TS_ - external_t / decay_sec_;  // 减去参考时间
cv::exp(representation_TS_, representation_TS_); // 指数衰减

	// 4.5 转换为图像格式
TS_img = representation_TS_ * 255.0;
TS_img.convertTo(TS_img, CV_8U);

对于TS的生成,TS_temp_map(e.y, e.x) = e.ts.toSec() / decay_sec_;对应指数因子的前半部分,而当我们用一个矩阵减去一个标量值时,OpenCV会自动将这个标量”广播”到与矩阵相同的尺寸,即对矩阵中的每个元素都减去这个标量值,对应representation_TS_ = representation_TS_ - external_t / decay_sec_。这样就与TS公式对应起来了。