Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

跑MARS Dataset时无人机一起飞终端就会报红挂掉 #108

Closed
maxibooksiyi opened this issue Jul 16, 2024 · 3 comments
Closed

跑MARS Dataset时无人机一起飞终端就会报红挂掉 #108

maxibooksiyi opened this issue Jul 16, 2024 · 3 comments

Comments

@maxibooksiyi
Copy link

我用FAST-LIVO跑MARS Dataset时无人机一起飞终端就会挂掉,换了好几个序列都是这样,包括AMtown AMvalley HKisland序列,无人机刚开始还在地面上放置时都是可以正常运行一段时间的,无人机一起飞到半空中,终端就会报红挂掉,或则我改为bag包播放到无人机飞到空中时再启动FAST-LIVO,终端基本上立马就报红挂掉,相机内参都已经改为MARS Dataset对应的相机内参了。想知道挂掉的原因是什么,以及该如何解决...
下面是挂掉时的一些终端截图
图片
图片
图片
图片

这是我的avia_resize.yaml的内容
`feature_extract_enable : 0
point_filter_num : 2
max_iteration : 10
dense_map_enable : 1
filter_size_surf : 0.15
filter_size_map : 0.3
cube_side_length : 20
debug : 0
grid_size : 40
patch_size : 8
img_enable : 1
lidar_enable : 1
outlier_threshold : 300 # 78 100 156
ncc_en: false
ncc_thre: 0
img_point_cov : 100 # 1000
laser_point_cov : 0.001 # 0.001
cam_fx: 1453.72
cam_fy: 1453.28
cam_cx: 1172.18
cam_cy: 1041.78

common:
lid_topic: "/livox/lidar"
imu_topic: "/livox/imu"

preprocess:
lidar_type: 1 # 1:Livox Avia LiDAR 2:VELO16 3:OUST64 4:XT32
scan_line: 6 # 16 64 32
blind: 5 # blind x m disable

mapping:
acc_cov_scale: 100
gyr_cov_scale: 10000
fov_degree: 90 # 360
extrinsic_T: [ 0.04165, 0.02326, -0.0284 ]
extrinsic_R: [ 1, 0, 0,
0, 1, 0,
0, 0, 1]

pcd_save:
pcd_save_en: true

camera:
# img_topic: /usb_cam/image_raw
# img_topic: /camera/image_color
img_topic: /left_camera/image
#xiyuan
Rcl: [0.00162756,-0.999991,0.00390957,
-0.0126748,-0.00392989,-0.999912,
0.999918,0.00157786,-0.012681]
Pcl: [0.0409257, 0.0318424, -0.0927219]
`

@xuankuzcr
Copy link
Member

xuankuzcr commented Jul 19, 2024

我刚才测了一下感觉没什么太大问题,截图结果如下。另外我一会儿单独为MARS-LVIG dataset创建一个配置文件然后push上去吧,方便大家复现,之后你可以再测试下哈。但最好你能用gdb检查下到底问题出在哪行#53,我比较担心是你的环境配置问题。
rviz_screenshot_2024_07_19-03_33_40
Screenshot from 2024-07-19 12-14-12
Screenshot from 2024-07-19 12-17-24
Screenshot from 2024-07-19 12-17-36
Screenshot from 2024-07-19 12-17-49

@maxibooksiyi
Copy link
Author

非常感谢您的回答,很有帮助,我用gdb调试后打印信息如下

[ VIO ]: Add 0 3D points.
[ VIO ]: time: addFromSparseMap: 0.000011 addSparseMap: 0.000055 ComputeJ: 0.000004 addObservation: 0.000002 total time: 0.000072 ave_total: 0.000072.
[ LIO ]: Raw feature num: 11893 downsamp num 10911 Map num: 10964.
[ LIO ]: Using multi-processor, used core number: 4.
[New Thread 0x7fff923f8700 (LWP 18464)]
[New Thread 0x7fff91bf7700 (LWP 18465)]
[New Thread 0x7fff913f6700 (LWP 18466)]
[ LIO ]: time: fov_check: 0.000000 fov_check and readd: 0.002638 match: 0.000000 solve: 0.000000  ICP: 0.001149  map incre: 0.031386 total: 0.035173 icp: 0.000780 construct H: 0.000000.
[ INFO ]: get point cloud at time: 1658137064.324880.
[ VIO ]: Raw feature num: 11893.
[ VIO ]: Add 1761 3D points.
[ VIO ]: time: addFromSparseMap: 0.000001 addSparseMap: 0.006574 ComputeJ: 0.000000 addObservation: 0.000000 total time: 0.006576 ave_total: 0.006576.
[ INFO ]: get img at time: 1658137064.440385.
[ LIO ]: Raw feature num: 11898 downsamp num 10905 Map num: 17091.
[ LIO ]: Using multi-processor, used core number: 4.
[ LIO ]: time: fov_check: 0.000000 fov_check and readd: 0.002378 match: 0.000000 solve: 0.000000  ICP: 0.002737  map incre: 0.020595 total: 0.030441 icp: 0.001689 construct H: 0.000000.
[ INFO ]: get img at time: 1658137064.540787.
[ INFO ]: get point cloud at time: 1658137064.424726.
[ VIO ]: Raw feature num: 11898.

Thread 1 "fastlivo_mappin" received signal SIGSEGV, Segmentation fault.
0x00007ffff32a6088 in lidar_selection::LidarSelector::addFromSparseMap (
    this=this@entry=0x55555c87d3c0, img=..., pg=...)
    at /home/maxi/FASTLIVO_ws/src/FAST-LIVO/src/lidar_selection.cpp:376
376         float it[height*width] = {0.0};
(gdb)

然后参考您给的 #53 ,我把lidar_selection.cpp的376行的float it[height * width] = {0.0};改为了std::vector it(height*width, 0); 再重新编译后运行,便可以基于MARS-LVIG dataset跑起来了。
但是运行不了多长时间(不到一分钟),终端就会报红挂掉,从gnome-system-monitor里面可以看到,FAST-LIVO运行起来后,内存占用一直在累积上升,到达百分之百之后程序终端就会卡住报红挂掉。我是普通笔记本上跑的,内存是16G。似乎和这个 #105 类似是么。
但在跑FAST-LIVO-Datasets里的hku1.bag是可以运行相对长点的时间而且跑完的。

%I_ Q}QLL$8UA8JHM6BN3Z1

@xuankuzcr
Copy link
Member

相同的地图分辨率,大尺度场景内存涨的会越快,因为每帧的raw points会有特别多的点被用来更新地图。可以试着调低filter_size_map,关掉rviz,或增加swap空间。另外我已经上传了MARS-LVIG的参数和launch文件,并为了适配做了一些的代码修改。如果想要速度更快,内存占用更低的版本,可以follow下FAST-LIVO2。

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants