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

simulated velodyne point cloud causing Segmentation fault (core dumped) on rtabmap/icp_odometry nodes #560

Open
matlabbe opened this issue Mar 28, 2021 · 2 comments

Comments

@matlabbe
Copy link
Member

Here is a backtrace from gdb:

thread 29 "icp_odometry" received signal SIGSEGV, Segmentation fault.
[Switching to Thread 0x7fffb0d25700 (LWP 154167)]
__memmove_avx_unaligned_erms () at ../sysdeps/x86_64/multiarch/memmove-vec-unaligned-erms.S:312
312	../sysdeps/x86_64/multiarch/memmove-vec-unaligned-erms.S: No such file or directory.
(gdb) bt
#0  __memmove_avx_unaligned_erms () at ../sysdeps/x86_64/multiarch/memmove-vec-unaligned-erms.S:312
#1  0x00007fffb0314245 in void pcl::fromPCLPointCloud2<pcl::PointXYZI>(pcl::PCLPointCloud2 const&, pcl::PointCloud<pcl::PointXYZI>&, std::vector<pcl::detail::FieldMapping, std::allocator<pcl::detail::FieldMapping> > const&) ()
    at /home/mathieu/catkin_ws/devel/lib//librtabmap_plugins.so
#2  0x00007fffb031b420 in void pcl::fromROSMsg<pcl::PointXYZI>(sensor_msgs::PointCloud2_<std::allocator<void> > const&, pcl::PointCloud<pcl::PointXYZI>&) () at /home/mathieu/catkin_ws/devel/lib//librtabmap_plugins.so
#3  0x00007fffb032247c in rtabmap_ros::ICPOdometry::callbackCloud(boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&) () at /home/mathieu/catkin_ws/devel/lib//librtabmap_plugins.so

The bug happens when converting the PointCloud2 message in PCL templated cloud version. It is crashing here.

The point cloud width/height/row_step are wrong. This bug seems coming from this commit in velodyne gazebo plugin. A solution is to invert the width and height values here to :

    msg.width = msg.data.size() / POINT_STEP;
    msg.height = 1;
@matlabbe
Copy link
Member Author

@matlabbe
Copy link
Member Author

Another workaround without recompiling the plugin is to use organized_cloud=true with the plugin, like this:

  <xacro:include filename="$(find velodyne_description)/urdf/VLP-16.urdf.xacro"/>
  <xacro:VLP-16 parent="base_laser_mount" name="velodyne" topic="velodyne_points" gpu="true" organize_cloud="true">
    <origin xyz="0.025 0 0.175" rpy="0 0 0" />
  </xacro:VLP-16>

matlabbe added a commit that referenced this issue Mar 28, 2021
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

1 participant