alsora / ros2-ORB_SLAM2

ROS2 node wrapping the ORB_SLAM2 library
GNU General Public License v3.0
130 stars 30 forks source link

Error: “double free or corruption (out)” #13

Closed EndlessLoops closed 1 year ago

EndlessLoops commented 1 year ago

Test Background: ubuntu 2204 + ros humble + opencv 4.5.4 + d435i When I run the rgbd example ,it crashes. And the mono example works fine.
I need some help on it.

Terminal output

$ ros2 run ros2_orbslam rgbd ~/ORB_SLAM2/Vocabulary/ORBvoc.txt ~/ros2_ws/src/ros2-ORB_SLAM2/src/rgbd/TUM1.yaml --ros-args --remap /camera/depth:=/camera/depth/image_rect_raw --ros-args --remap /camera/rgb:=/camera/color/image_raw

ORB-SLAM2 Copyright (C) 2014-2016 Raul Mur-Artal, University of Zaragoza.
This program comes with ABSOLUTELY NO WARRANTY;
This is free software, and you are welcome to redistribute it
under certain conditions. See LICENSE.txt.

Input sensor was set to: RGB-D

Loading ORB Vocabulary. This could take a while...
Vocabulary loaded!

Camera Parameters: 
- fx: 517.306
- fy: 516.469
- cx: 318.643
- cy: 255.314
- k1: 0.262383
- k2: -0.953104
- k3: 1.16331
- p1: -0.005358
- p2: 0.002628
- fps: 30
- color order: RGB (ignored if grayscale)

ORB Extractor Parameters: 
- Number of Features: 1000
- Scale Levels: 8
- Scale Factor: 1.2
- Initial Fast Threshold: 20
- Minimum Fast Threshold: 7

Depth Threshold (Close/Far Points): 3.09294

Saving keyframe trajectory to KeyFrameTrajectory.txt ...

trajectory saved!
double free or corruption (out)
[ros2run]: Aborted

gdb log

#0  __pthread_kill_implementation (no_tid=0, signo=6, threadid=140736998887936) at ./nptl/pthread_kill.c:44
#1  __pthread_kill_internal (signo=6, threadid=140736998887936) at ./nptl/pthread_kill.c:78
#2  __GI___pthread_kill (threadid=140736998887936, signo=signo@entry=6) at ./nptl/pthread_kill.c:89
#3  0x00007ffff6c42476 in __GI_raise (sig=sig@entry=6) at ../sysdeps/posix/raise.c:26
#4  0x00007ffff6c287f3 in __GI_abort () at ./stdlib/abort.c:79
#5  0x00007ffff6c896f6 in __libc_message (action=action@entry=do_abort, fmt=fmt@entry=0x7ffff6ddbb8c "%s\n") at ../sysdeps/posix/libc_fatal.c:155
#6  0x00007ffff6ca0d7c in malloc_printerr (str=str@entry=0x7ffff6dde7b0 "double free or corruption (out)") at ./malloc/malloc.c:5664
#7  0x00007ffff6ca2ef0 in _int_free (av=0x7ffff6e19c80 <main_arena>, p=0x555555c05e60, have_lock=<optimized out>) at ./malloc/malloc.c:4588
#8  0x00007ffff6ca54d3 in __GI___libc_free (mem=<optimized out>) at ./malloc/malloc.c:3391
#9  0x000055555556eb2b in RgbdSlamNode::~RgbdSlamNode() ()
#10 0x00005555555ff5cc in std::_Sp_counted_ptr<RgbdSlamNode*, (__gnu_cxx::_Lock_policy)2>::_M_dispose() ()
#11 0x000055555556cfe1 in std::_Sp_counted_base<(__gnu_cxx::_Lock_policy)2>::_M_release() ()
#12 0x000055555556cb7b in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::~__shared_count() ()
#13 0x000055555556ca60 in std::__shared_ptr<rclcpp::Node, (__gnu_cxx::_Lock_policy)2>::~__shared_ptr() ()
#14 0x000055555556ca80 in std::shared_ptr<rclcpp::Node>::~shared_ptr() ()
#15 0x000055555558858a in void __gnu_cxx::new_allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> >::construct<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node>, std::shared_ptr<rclcpp::Node>, char const (&) [11]>(message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node>*, std::shared_ptr<rclcpp::Node>&&, char const (&) [11]) ()
#16 0x0000555555586b88 in void std::allocator_traits<std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> > >::construct<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node>, std::shared_ptr<rclcpp::Node>, char const (&) [11]>(std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> >&, message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node>*, std::shared_ptr<rclcpp::Node>&&, char const (&) [11]) ()
#17 0x0000555555584c75 in std::_Sp_counted_ptr_inplace<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node>, std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> >, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<std::shared_ptr<rclcpp::Node>, char const (&) [11]>(std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> >, std::shared_ptr<rclcpp::Node>&&, char const (&) [11]) ()
#18 0x00005555555827e9 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node>, std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> >, std::shared_ptr<rclcpp::Node>, char const (&) [11]>(message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node>*&, std::_Sp_alloc_shared_tag<std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> > >, std::shared_ptr<rclcpp::Node>&&, char const (&) [11]) ()
#19 0x0000555555580268 in std::__shared_ptr<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node>, (__gnu_cxx::_Lock_policy)2>::__shared_ptr<std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> >, std::shared_ptr<rclcpp::Node>, char const (&) [11]>(std::_Sp_alloc_shared_tag<std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> > >, std::shared_ptr<rclcpp::Node>&&, char const (&) [11]) ()
#20 0x000055555557d6f9 in std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> >::shared_ptr<std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> >, std::shared_ptr<rclcpp::Node>, char const (&) [11]>(std::_Sp_alloc_shared_tag<std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> > >, std::shared_ptr<rclcpp::Node>&&, char const (&) [11]) ()
#21 0x000055555557aa37 in std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> > std::allocate_shared<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node>, std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> >, std::shared_ptr<rclcpp::Node>, char const (&) [11]>(std::allocator<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> > const&, std::shared_ptr<rclcpp::Node>&&, char const (&) [11]) ()
#22 0x0000555555577b8a in std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node> > std::make_shared<message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> >, rclcpp::Node>, std::shared_ptr<rclcpp::Node>, char const (&) [11]>(std::shared_ptr<rclcpp::Node>&&, char const (&) [11]) ()
#23 0x000055555556e6f3 in RgbdSlamNode::RgbdSlamNode(ORB_SLAM2::System*) ()
#24 0x000055555556e15b in void __gnu_cxx::new_allocator<RgbdSlamNode>::construct<RgbdSlamNode, ORB_SLAM2::System*>(RgbdSlamNode*, ORB_SLAM2::System*&&) ()
#25 0x000055555556df9a in void std::allocator_traits<std::allocator<RgbdSlamNode> >::construct<RgbdSlamNode, ORB_SLAM2::System*>(std::allocator<RgbdSlamNode>&, RgbdSlamNode*, ORB_SLAM2::System*&&) ()
#26 0x000055555556dd80 in std::_Sp_counted_ptr_inplace<RgbdSlamNode, std::allocator<RgbdSlamNode>, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<ORB_SLAM2::System*>(std::allocator<RgbdSlamNode>, ORB_SLAM2::System*&&) ()
#27 0x000055555556da26 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count<RgbdSlamNode, std::allocator<RgbdSlamNode>, ORB_SLAM2::System*>(RgbdSlamNode*&, std::_Sp_alloc_shared_tag<std::allocator<RgbdSlamNode> >, ORB_SLAM2::System*&&) ()
#28 0x000055555556d922 in std::__shared_ptr<RgbdSlamNode, (__gnu_cxx::_Lock_policy)2>::__shared_ptr<std::allocator<RgbdSlamNode>, ORB_SLAM2::System*>(std::_Sp_alloc_shared_tag<std::allocator<RgbdSlamNode> >, ORB_SLAM2::System*&&) ()
#29 0x000055555556d76b in std::shared_ptr<RgbdSlamNode>::shared_ptr<std::allocator<RgbdSlamNode>, ORB_SLAM2::System*>(std::_Sp_alloc_shared_tag<std::allocator<RgbdSlamNode> >, ORB_SLAM2::System*&&) ()
#30 0x000055555556d531 in std::shared_ptr<RgbdSlamNode> std::allocate_shared<RgbdSlamNode, std::allocator<RgbdSlamNode>, ORB_SLAM2::System*>(std::allocator<RgbdSlamNode> const&, ORB_SLAM2::System*&&) ()
#31 0x000055555556ce85 in std::shared_ptr<RgbdSlamNode> std::make_shared<RgbdSlamNode, ORB_SLAM2::System*>(ORB_SLAM2::System*&&) ()
#32 0x000055555556c168 in main ()
EndlessLoops commented 1 year ago

Fixed.

rgbd-slam-node.cpp

    //rgb_sub = std::make_shared<message_filters::Subscriber<ImageMsg> >(shared_ptr<rclcpp::Node>(this), "camera/rgb");
    //depth_sub = std::make_shared<message_filters::Subscriber<ImageMsg> >(shared_ptr<rclcpp::Node>(this), "camera/depth");
    rgb_sub = std::make_shared<message_filters::Subscriber<ImageMsg>>(this, "/camera/color/image_raw");
    depth_sub = std::make_shared<message_filters::Subscriber<ImageMsg>>(this, "/camera/depth/image_rect_raw");
Unknown9190 commented 6 months ago

for anyone wandering, If you got the error of `double free or corruption (out)

most of the time it is because of the above issue, just change the shared_ptr<rclcpp::Node>(this) to this