FAST-LIVO2 icon indicating copy to clipboard operation
FAST-LIVO2 copied to clipboard

程序运行不足十分钟,内存溢出?

Open newhuman88 opened this issue 8 months ago • 20 comments

@xuankuzcr 你好,现阶段在运行FAST-Livo2时遇到内存溢出的问题,本机一共16G内存,运行10分钟程序就因内存太大结束 之后通过valgrand发现大量多余的数据没有释放

Image 通过上图分析,分别是OpenCV以及Eigen库占据了大量的内存空间,如下图所示,程序本身占用内存空间一直稳定在1G左右

Image

之后查看版本

Image 发现OpenCV版本是3.2.0,Eigen的版本是3.3.4 PCL版本是1.8.1 只有OpenCV的版本没达到要求的4.2.0 是否是由于OpenCV版本没有到位,导致fast-livo2程序运行时内存暂用太大,不能及时释放内存吗 还是由什么问题造成 还是需要什么来分析这个程序运行内存太大的问题 麻烦解惑,谢谢!

newhuman88 avatar Apr 26 '25 06:04 newhuman88

@XW-HKU @xuankuzcr 后续使用给的标准包文件,也会出现内存不断增加的情况,就是此链接,也就是示例bag包,运行这个包,并启动程序后,内存大概运行到8G左右。就这两个步骤 roslaunch fast_livo mapping_avia.launch rosbag play YOUR_DOWNLOADED.bag 现阶段就不清楚应该怎么样才能解决这个问题(或者是自身哪里出错了),麻烦指点,谢谢!

newhuman88 avatar May 05 '25 05:05 newhuman88

可以参考https://github.com/hku-mars/FAST-LIVO2/issues/224 修改为LRU机制及时释放用不上的体素

yqmy0814 avatar May 06 '25 02:05 yqmy0814

@yqmy0814 你好,之前就利用这个程序改过224,但是会出现更严重的问题(程序运行不完整就死机),可能是根据此程序,改的部分不能很好的兼容此程序 这个更改程序后的运行问题

Image 程序内容和224差不多 `// 加在类成员里 std::list<std::pair<VOXEL_LOCATION, VoxelOctoTree*>> voxel_map_cache_; std::unordered_map<VOXEL_LOCATION, std::list<std::pair<VOXEL_LOCATION, VoxelOctoTree*>>::iterator> voxel_map_; const size_t MAX_VOXEL_NUM = 20000; // 可配置

void VoxelMapManager::UpdateVoxelMap(const std::vector<pointWithVar> &input_points) { float voxel_size = config_setting_.max_voxel_size_; float planer_threshold = config_setting_.planner_threshold_; int max_layer = config_setting_.max_layer_; int max_points_num = config_setting_.max_points_num_; std::vector layer_init_num = config_setting_.layer_init_num_; uint plsize = input_points.size();

for (uint i = 0; i < plsize; i++) { const pointWithVar &p_v = input_points[i]; float loc_xyz[3]; for (int j = 0; j < 3; j++) { loc_xyz[j] = p_v.point_w[j] / voxel_size; if (loc_xyz[j] < 0) { loc_xyz[j] -= 1.0f; } }

VOXEL_LOCATION position((int64_t)loc_xyz[0], (int64_t)loc_xyz[1], (int64_t)loc_xyz[2]);
auto it = voxel_map_.find(position);

if (it != voxel_map_.end())
{
  // -------- 已存在体素:更新访问顺序 + 更新内容 --------
  voxel_map_cache_.splice(voxel_map_cache_.begin(), voxel_map_cache_, it->second);
  VoxelOctoTree* voxel = it->second->second;
  voxel->UpdateOctoTree(p_v);
}
else
{
  // -------- 新体素:初始化并插入 --------
  VoxelOctoTree *octo_tree = new VoxelOctoTree(max_layer, 0, layer_init_num[0], max_points_num, planer_threshold);
  octo_tree->layer_init_num_ = layer_init_num;
  octo_tree->quater_length_ = voxel_size / 4.0f;
  octo_tree->voxel_center_[0] = (0.5f + position.x) * voxel_size;
  octo_tree->voxel_center_[1] = (0.5f + position.y) * voxel_size;
  octo_tree->voxel_center_[2] = (0.5f + position.z) * voxel_size;
  octo_tree->UpdateOctoTree(p_v);

  // 插入到前面(最近使用)
  voxel_map_cache_.emplace_front(position, octo_tree);

  // 更新哈希表
  voxel_map_[position] = voxel_map_cache_.begin();

  // -------- 检查是否超出体素上限 --------
  if (voxel_map_cache_.size() > MAX_VOXEL_NUM)
  {
    auto old_it = std::prev(voxel_map_cache_.end());

    // 删除最旧体素
    voxel_map_.erase(old_it->first);
    delete old_it->second;
    voxel_map_cache_.pop_back();
  }
}

} }` 但就是会出现这个错误,可能是没有考虑到整体性,是否有完整的附件内容,还是我哪里没有考虑全面,麻烦指点,谢谢

newhuman88 avatar May 06 '25 03:05 newhuman88

这不是具体代码,这是大概的内容,具体程序之后附上

newhuman88 avatar May 06 '25 03:05 newhuman88

感觉更新这里是有问题的,可以参考issue里letterso的代码,先更新内容再换位置试试

yqmy0814 avatar May 06 '25 03:05 yqmy0814

@yqmy0814 你好,根据你刚刚的要求进行了更改,为了适应编译要求,对程序进行了相应更改,程序如下:

std::unordered_map<VOXEL_LOCATION, VoxelOctoTree > voxel_map_; std::list<std::pair<VOXEL_LOCATION, VoxelOctoTree>> voxel_map_cache_; std::unordered_map<VOXEL_LOCATION, std::list<std::pair<VOXEL_LOCATION, VoxelOctoTree*>>::iterator> cache_iterator_map_; void VoxelMapManager::UpdateVoxelMap(const std::vector<pointWithVar>& input_points) { const float voxel_size = config_setting_.max_voxel_size_; const float planer_threshold = config_setting_.planner_threshold_; const int max_layer = config_setting_.max_layer_; const int max_points_num = config_setting_.max_points_num_; const std::vector layer_init_num = config_setting_.layer_init_num_; const size_t plsize = input_points.size();

for (size_t i = 0; i < plsize; ++i)
{
    const pointWithVar& p_v = input_points[i];
    float loc_xyz[3];
    for (int j = 0; j < 3; ++j)
    {
        loc_xyz[j] = p_v.point_w[j] / voxel_size;
        if (loc_xyz[j] < 0) loc_xyz[j] -= 1.0f;
    }
    VOXEL_LOCATION position((int64_t)loc_xyz[0], (int64_t)loc_xyz[1], (int64_t)loc_xyz[2]);
    auto iter = voxel_map_.find(position);

    if (iter != voxel_map_.end())
    {
        // 更新 OctoTree
        iter->second->UpdateOctoTree(p_v);

        auto cache_iter_it = cache_iterator_map_.find(position);
        if (cache_iter_it != cache_iterator_map_.end())
        {
          voxel_map_cache_.splice(voxel_map_cache_.begin(), voxel_map_cache_, cache_iter_it->second);
        }
        else
        {
          // 安全保障(理论上不该发生)
          ROS_WARN("Cache iterator for voxel not found, but voxel exists!");
        }
    }
    else
    {
        // 创建新的 OctoTree
        VoxelOctoTree* octo_tree = new VoxelOctoTree(max_layer, 0, layer_init_num[0], max_points_num, planer_threshold);
        octo_tree->quater_length_ = voxel_size / 4;
        octo_tree->voxel_center_[0] = (0.5 + position.x) * voxel_size;
        octo_tree->voxel_center_[1] = (0.5 + position.y) * voxel_size;
        octo_tree->voxel_center_[2] = (0.5 + position.z) * voxel_size;
        octo_tree->temp_points_.push_back(p_v);
        octo_tree->new_points_++;
        octo_tree->layer_init_num_ = layer_init_num;

        // 插入到 cache 头部
        voxel_map_cache_.emplace_front(position, octo_tree);
        cache_iterator_map_[position] = voxel_map_cache_.begin();
        voxel_map_[position] = octo_tree;
    }
}

// 缓存容量限制(建议在类中定义 CAPACITY)
while (voxel_map_cache_.size() > CAPACITY && !voxel_map_cache_.empty())
{
    auto last = voxel_map_cache_.back();
    delete last.second;
    voxel_map_.erase(last.first);
    cache_iterator_map_.erase(last.first);
    voxel_map_cache_.pop_back();
}

}

` 利用这个程序跑示例包,内存相对减少1G左右,但当例程停下来后,机械人跑丢了,如下图,没有回归原始位置

Image 利用内存分析工具分析,现阶段的内存泄漏如下图:

Image 是我哪里更改的有问题吗,麻烦指点

newhuman88 avatar May 06 '25 07:05 newhuman88

splice后面要再加一句更新一下指针戳的位置,这样修改一下试试 iter->second = cache_iterator_map_.begin();

yqmy0814 avatar May 06 '25 08:05 yqmy0814

@yqmy0814 是对程序这样更改吗 ` void VoxelMapManager::UpdateVoxelMap(const std::vector<pointWithVar>& input_points) { const float voxel_size = config_setting_.max_voxel_size_; const float planer_threshold = config_setting_.planner_threshold_; const int max_layer = config_setting_.max_layer_; const int max_points_num = config_setting_.max_points_num_; const std::vector layer_init_num = config_setting_.layer_init_num_;

const size_t plsize = input_points.size();

for (size_t i = 0; i < plsize; ++i)
{
    const pointWithVar& p_v = input_points[i];
    float loc_xyz[3];
    for (int j = 0; j < 3; ++j)
    {
        loc_xyz[j] = p_v.point_w[j] / voxel_size;
        if (loc_xyz[j] < 0) loc_xyz[j] -= 1.0f;
    }
    VOXEL_LOCATION position((int64_t)loc_xyz[0], (int64_t)loc_xyz[1], (int64_t)loc_xyz[2]);
    auto iter = voxel_map_.find(position);

    if (iter != voxel_map_.end())
    {
    // 更新 OctoTree
    iter->second->UpdateOctoTree(p_v);

    // 查找该体素在 cache 中的迭代器
    auto cache_iter_it = cache_iterator_map_.find(position);
    if (cache_iter_it != cache_iterator_map_.end())
    {
        // 将该节点移动到 cache 头部
        voxel_map_cache_.splice(voxel_map_cache_.begin(), voxel_map_cache_, cache_iter_it->second);

        // 更新 map 中的迭代器为新的头部位置
        cache_iterator_map_[position] = voxel_map_cache_.begin();
    }
        else
        {
          // 安全保障
          ROS_WARN("Cache iterator for voxel not found, but voxel exists!");
        }
    }
    else
    {
        // 创建新的 OctoTree
        VoxelOctoTree* octo_tree = new VoxelOctoTree(max_layer, 0, layer_init_num[0], max_points_num, planer_threshold);
        octo_tree->quater_length_ = voxel_size / 4;
        octo_tree->voxel_center_[0] = (0.5 + position.x) * voxel_size;
        octo_tree->voxel_center_[1] = (0.5 + position.y) * voxel_size;
        octo_tree->voxel_center_[2] = (0.5 + position.z) * voxel_size;
        octo_tree->temp_points_.push_back(p_v);
        octo_tree->new_points_++;
        octo_tree->layer_init_num_ = layer_init_num;

        // 插入到 cache 头部
        voxel_map_cache_.emplace_front(position, octo_tree);
        cache_iterator_map_[position] = voxel_map_cache_.begin();
        voxel_map_[position] = octo_tree;
    }
}

// 缓存容量限制
while (voxel_map_cache_.size() > CAPACITY && !voxel_map_cache_.empty())
{
    auto last = voxel_map_cache_.back();
    delete last.second;
    voxel_map_.erase(last.first);
    cache_iterator_map_.erase(last.first);
    voxel_map_cache_.pop_back();
}

}

` 是这样更改吗? 如果是这样更改,不行,程序运行非常卡顿,示例包运行到一半16G内存直接爆了

newhuman88 avatar May 06 '25 08:05 newhuman88

不是这样,你参考一下这段代码吧

inline void UpdateVoxelMapLRU(
    const std::vector<PointWithCov> &input_points, const float voxel_size,
    const int max_layer, const std::vector<int> &layer_point_size,
    const int max_points_size, const int max_cov_points_size,
    const float planer_threshold,
    std::unordered_map<VOXEL_LOC, typename std::list<VMData>::iterator> &vm_map,
    std::list<VMData> &vm_data) {
  uint plsize = input_points.size();

  for (uint i = 0; i < plsize; i++) {
    const PointWithCov p_v = input_points[i];
    // 计算voxel坐标
    float loc_xyz[3];
    for (int j = 0; j < 3; j++) {
      loc_xyz[j] = p_v.point_lidar[j] / voxel_size;
      if (loc_xyz[j] < 0) {
        loc_xyz[j] -= 1.0;
      }
    }
    VOXEL_LOC position((int64_t)loc_xyz[0], (int64_t)loc_xyz[1],
                       (int64_t)loc_xyz[2]);
    auto iter = vm_map.find(position);
    // 如果点的位置已经存在voxel 那么就更新点的位置 否则创建新的voxel
    if (iter != vm_map.end()) {
      vm_map[position]->second.UpdateOctoTree(p_v);
      // 更新的放至最前
      vm_data.splice(vm_data.begin(), vm_data, iter->second);
      iter->second = vm_data.begin();
    } else {
      VMOctoTree octo_tree =
          VMOctoTree(max_layer, 0, layer_point_size, max_points_size,
                     max_cov_points_size, planer_threshold);
      vm_data.push_front({position, {octo_tree}});
      vm_map.insert({position, vm_data.begin()});

      // LRU
      if (vm_data.size() >= lru_size) {
        // 删除一个尾部的数据
        vm_map.erase(vm_data.back().first);
        vm_data.pop_back();
      }

      vm_map[position]->second.quater_length_ = voxel_size / 4;
      vm_map[position]->second.voxel_center_[0] =
          (0.5 + position.x) * voxel_size;
      vm_map[position]->second.voxel_center_[1] =
          (0.5 + position.y) * voxel_size;
      vm_map[position]->second.voxel_center_[2] =
          (0.5 + position.z) * voxel_size;
      vm_map[position]->second.UpdateOctoTree(p_v);
    }
  }
}

yqmy0814 avatar May 06 '25 08:05 yqmy0814

@yqmy0814 你好,根据你的示例程序,程序更改如下 ` void VoxelMapManager::UpdateVoxelMap(const std::vector& input_points) { const float voxel_size = config_setting_.max_voxel_size_; const float planer_threshold = config_setting_.planner_threshold_; const int max_layer = config_setting_.max_layer_; const int max_points_num = config_setting_.max_points_num_; const std::vector layer_init_num = config_setting_.layer_init_num_;

const size_t plsize = input_points.size();

for (size_t i = 0; i < plsize; ++i) { const pointWithVar& p_v = input_points[i]; float loc_xyz[3]; for (int j = 0; j < 3; ++j) { loc_xyz[j] = p_v.point_w[j] / voxel_size; if (loc_xyz[j] < 0) loc_xyz[j] -= 1.0f; } VOXEL_LOCATION position((int64_t)loc_xyz[0], (int64_t)loc_xyz[1], (int64_t)loc_xyz[2]); auto iter = voxel_map_.find(position);

if (iter != voxel_map_.end())
{
// 更新 OctoTree
iter->second->UpdateOctoTree(p_v);

// 查找该体素在 cache 中的迭代器
auto cache_iter_it = cache_iterator_map_.find(position);
if (cache_iter_it != cache_iterator_map_.end())
{
    // 将该节点移动到 cache 头部
    voxel_map_cache_.splice(voxel_map_cache_.begin(), voxel_map_cache_, cache_iter_it->second);

    // 更新 map 中的迭代器为新的头部位置
    cache_iter_it->second  = voxel_map_cache_.begin();
}
    else
    {
      // 安全保障
      ROS_WARN("Cache iterator for voxel not found, but voxel exists!");
    }
}
else
{
    // 创建新的 OctoTree
    VoxelOctoTree* octo_tree = new VoxelOctoTree(max_layer, 0, layer_init_num[0], max_points_num, planer_threshold);
    octo_tree->quater_length_ = voxel_size / 4;
    octo_tree->voxel_center_[0] = (0.5 + position.x) * voxel_size;
    octo_tree->voxel_center_[1] = (0.5 + position.y) * voxel_size;
    octo_tree->voxel_center_[2] = (0.5 + position.z) * voxel_size;
    octo_tree->temp_points_.push_back(p_v);
    octo_tree->new_points_++;
    octo_tree->layer_init_num_ = layer_init_num;

    // 插入到 cache 头部
    voxel_map_cache_.emplace_front(position, octo_tree);
    cache_iterator_map_[position] = voxel_map_cache_.begin();
    voxel_map_[position] = octo_tree;
}

}

// 缓存容量限制 while (voxel_map_cache_.size() > CAPACITY && !voxel_map_cache_.empty()) { auto last = voxel_map_cache_.back(); delete last.second; voxel_map_.erase(last.first); cache_iterator_map_.erase(last.first); voxel_map_cache_.pop_back(); } `

运行上述程序,内存相对于减少2G左右,但是 运行示例包机械人跑丢了,如下图:

Image

是我没有完整了理解整个程序,缺少整体逻辑性吗? 麻烦指点下,谢谢!

newhuman88 avatar May 06 '25 12:05 newhuman88

std::unordered_map<VOXEL_LOCATION, VoxelOctoTree > voxel_map_;这个变量是不需要的,只需要一个list存放实际数据,一个哈希表存放list的迭代器

yqmy0814 avatar May 07 '25 01:05 yqmy0814

你先参考这几张PPT理解一下LRU机制吧

Image

Image

Image

Image

yqmy0814 avatar May 07 '25 01:05 yqmy0814

@yqmy0814 你好,根据你的建议,对程序进行了优化,然后优化为两个变量发现改变该部分需要更改其他程序部分,需要点时间,谢谢指点!

newhuman88 avatar May 08 '25 07:05 newhuman88

std::unordered_map<VOXEL_LOCATION, VoxelOctoTree > voxel_map_;这个变量是不需要的,只需要一个list存放实际数据,一个哈希表存放list的迭代器

大佬可以上传一下代码学习一下吗

hujiax380 avatar May 08 '25 08:05 hujiax380

std::unordered_map<VOXEL_LOCATION, VoxelOctoTree > voxel_map_;这个变量是不需要的,只需要一个list存放实际数据,一个哈希表存放list的迭代器

大佬可以上传一下代码学习一下吗

这个改动不难的,参考https://github.com/gaoxiang12/slam_in_autonomous_driving ch7中ndt3d和ndtinc就分别是没有LRU和有LRU的,对照一下去修改voxel map部分就可以了

yqmy0814 avatar May 08 '25 08:05 yqmy0814

我这边修改好了,可以参考修改 https://github.com/yqmy0814/FAST-LIVO2

yqmy0814 avatar May 27 '25 06:05 yqmy0814

@yqmy0814 你好,谢谢你的反馈,刚刚用你的程序编译运行了,但是只能运行3分钟,内存就溢出了,像素设置是1440*1080 请问你的配置是什么,尝试的能够运行多久

newhuman88 avatar May 28 '25 07:05 newhuman88

@yqmy0814 你好,谢谢你的反馈,刚刚用你的程序编译运行了,但是只能运行3分钟,内存就溢出了,像素设置是1440*1080 请问你的配置是什么,尝试的能够运行多久

我只跑了readme中提供的数据集,你这边的情况只能你自己分析了。另外lio和vio都有lru_size_这个变量,你可以调节看一下

yqmy0814 avatar May 28 '25 09:05 yqmy0814

好的,谢谢,感谢你的帮助

newhuman88 avatar May 28 '25 09:05 newhuman88

@newhuman88 请问一下你最后解决了吗?怎么解决的,我遇到和你差不多的问题

Epiphany-f avatar Nov 19 '25 03:11 Epiphany-f