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

Segmentation fault (core dumped) #35

Open
Fedioo opened this issue Apr 7, 2022 · 2 comments
Open

Segmentation fault (core dumped) #35

Fedioo opened this issue Apr 7, 2022 · 2 comments

Comments

@Fedioo
Copy link

Fedioo commented Apr 7, 2022

the Function pcl::fromROSMsg in lidar_detector/src/lib/node_lib.cpp is showing that error. any help please!

@RonaldEnsing
Copy link
Member

It is difficult to look into this without having the exact steps of how to reproduce.

@DevonMorris
Copy link

I dug into this a bit today with gdb. It comes down to the pattern variable not having size 4 after processCircles. Here is the backtrace.

#0  index_eigen_matrix2D (in=..., indices=...) at /ws/src/common/src/robust_least_squares.cpp:258
#1  0x00007f2e22a1dc37 in findCorrespondences2D (in=..., out=..., all_permutations=...) at /ws/src/common/src/robust_least_squares.cpp:302
#2  0x00007f2e22a1e400 in refine2D (calibration_board=..., detections_3d=..., threshold_inlier=threshold_inlier@entry=0.019999999552965164)
    at /ws/src/common/src/robust_least_squares.cpp:392
#3  0x00007f2e28c3c793 in lidar_detector::refinement (pattern=..., config=...) at /ws/src/lidar_detector/src/lib/keypoint_detection.cpp:366
#4  0x00007f2e28c41481 in lidar_detector::keypointDetection (in=..., config=...) at /ws/src/lidar_detector/src/lib/keypoint_detection.cpp:401
#5  0x00007f2e2b1328e5 in lidar_detector::LidarDetectorNode::callback (this=0x7ffee674ef80, in=...) at /ws/src/lidar_detector/src/lib/node_lib.cpp:66
#6  0x00007f2e2b13940e in boost::function1<void, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&>::operator() (a0=...,
    this=<optimized out>) at /usr/include/boost/function/function_template.hpp:759
#7  boost::detail::function::void_function_obj_invoker1<boost::function<void (boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&)>, void, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> >::invoke(boost::detail::function::function_buffer&, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const>) (function_obj_ptr=..., a0=...) at /usr/include/boost/function/function_template.hpp:159
#8  0x00007f2e2b13fc76 in boost::function1<void, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> >::operator() (a0=..., this=0x55e04f8e6fe8)
    at /usr/include/boost/function/function_template.hpp:759
#9  ros::SubscriptionCallbackHelperT<boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&, void>::call (this=0x55e04f8e6fe0, params=...)
    at /opt/ros/melodic/include/ros/subscription_callback_helper.h:144
#10 0x00007f2e29ba4e92 in ros::SubscriptionQueue::call() () from /opt/ros/melodic/lib/libroscpp.so
#11 0x00007f2e29b4f559 in ros::CallbackQueue::callOneCB(ros::CallbackQueue::TLS*) () from /opt/ros/melodic/lib/libroscpp.so
#12 0x00007f2e29b512fb in ros::CallbackQueue::callAvailable(ros::WallDuration) () from /opt/ros/melodic/lib/libroscpp.so
#13 0x00007f2e29ba8a39 in ros::SingleThreadedSpinner::spin(ros::CallbackQueue*) () from /opt/ros/melodic/lib/libroscpp.so
#14 0x00007f2e29b9137b in ros::spin() () from /opt/ros/melodic/lib/libroscpp.so
#15 0x000055e04dc07e17 in main (argc=<optimized out>, argv=<optimized out>) at /ws/src/lidar_detector/src/node.cpp:29

In frame 3, you can see that pattern is empty

(gdb) p pattern
$13 = {_vptr.PointCloud = 0x7f2e2b347400 <vtable for pcl::PointCloud<pcl::PointXYZ>+16>, header = {seq = 0, stamp = 0, frame_id = ""},
  points = std::vector of length 0, capacity 0, width = 0, height = 0, is_dense = true,
  sensor_origin_ = {<Eigen::PlainObjectBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> >> = {<Eigen::MatrixBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> >> = {<Eigen::DenseBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> >> = {<Eigen::DenseCoeffsBase<Eigen::Matrix<float, 4, 1, 0, 4, 1>, 3>> = {<Eigen::DenseCoeffsBase<Eigen::Matrix<float, 4, 1, 0, 4, 1>, 1>> = {<Eigen::DenseCoeffsBase<Eigen::Matrix<float, 4, 1, 0, 4, 1>, 0>> = {<Eigen::EigenBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> >> = {<No data fields>}, <No data fields>}, <No data fields>}, <No data fields>}, <No data fields>}, <No data fields>}, m_storage = {m_data = {array = {0, 0, 0, 0}}}}, <No data fields>},
  sensor_orientation_ = {<Eigen::QuaternionBase<Eigen::Quaternion<float, 0> >> = {<Eigen::RotationBase<Eigen::Quaternion<float, 0>, 3>> = {<No data fields>}, <No data fields>},
    m_coeffs = {<Eigen::PlainObjectBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> >> = {<Eigen::MatrixBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> >> = {<Eigen::DenseBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> >> = {<Eigen::DenseCoeffsBase<Eigen::Matrix<float, 4, 1, 0, 4, 1>, 3>> = {<Eigen::DenseCoeffsBase<Eigen::Matrix<float, 4, 1, 0, 4, 1>, 1>> = {<Eigen::DenseCoeffsBase<Eigen::Matrix<float, 4, 1, 0, 4, 1>, 0>> = {<Eigen::EigenBase<Eigen::Matrix<float, 4, 1, 0, 4, 1> >> = {<No data fields>}, <No data fields>}, <No data fields>}, <No data fields>}, <No data fields>}, <No data fields>}, m_storage = {m_data = {array = {0, 0, 0, 1}}}}, <No data fields>}}, mapping_ = {px = 0x0, pn = {
      pi_ = 0x0}}}

I believe the cause of this is due to processCircles having no error checking to ensure at least 4 points were found https://github.com/tudelft-iv/multi_sensor_calibration/blob/master/lidar_detector/src/lib/keypoint_detection.cpp#L278

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

3 participants