Closed EndlessLoops closed 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");
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
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
gdb log