You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
A common pattern in MULLS is to build instances of pcl::PointCloud by appending points directly into the underlying vector points using ->points.push_back.
This leaves the object in an invalid state, as the member attributes pcl::PointCloud::width and height are out-of-sync with the actual size. This can especially cause problems when passing such an object to an external library, as is the case with the map viewer.
Please consider using pcl::PointCloud.push_back instead of pcl::PointCloud::points.push_back.
This issue might be part of the reason for a program crash I am experiencing while having the map viewer enabled:
terminate called after throwing an instance of 'std::length_error'
what(): vector::reserve
Aborted (core dumped)
GDB stacktrace
terminate called after throwing an instance of 'std::length_error'
what(): vector::reserve
--Type <RET> for more, q to quit, c to continue without paging-- c
Thread 1 "mulls_slam" received signal SIGABRT, Aborted.
__GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:50
50 ../sysdeps/unix/sysv/linux/raise.c: No such file or directory.
(gdb) bt
#0 __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:50
#1 0x00007fffee56f859 in __GI_abort () at abort.c:79
#2 0x00007fffee949911 in () at /lib/x86_64-linux-gnu/libstdc++.so.6
#3 0x00007fffee95538c in () at /lib/x86_64-linux-gnu/libstdc++.so.6
#4 0x00007fffee9553f7 in () at /lib/x86_64-linux-gnu/libstdc++.so.6
#5 0x00007fffee9556a9 in () at /lib/x86_64-linux-gnu/libstdc++.so.6
#6 0x00007fffee94c326 in std::__throw_length_error(char const*) () at /lib/x86_64-linux-gnu/libstdc++.so.6
#7 0x00007ffff6249d9c in () at /lib/x86_64-linux-gnu/libpcl_features.so.1.10
#8 0x00007ffff02355bf in vtkOpenGLIndexBufferObject::AppendPointIndexBuffer(std::vector<unsigned int, std::allocator<unsigned int> >&, vtkCellArray*, long long) ()
at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#9 0x00007ffff02358af in vtkOpenGLIndexBufferObject::CreatePointIndexBuffer(vtkCellArray*) () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#10 0x00007ffff02a94e0 in vtkOpenGLPolyDataMapper::BuildIBO(vtkRenderer*, vtkActor*, vtkPolyData*) () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#11 0x00007ffff02ad166 in vtkOpenGLPolyDataMapper::BuildBufferObjects(vtkRenderer*, vtkActor*) () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#12 0x00007ffff02b15dc in vtkOpenGLPolyDataMapper::RenderPieceStart(vtkRenderer*, vtkActor*) () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#13 0x00007ffff02a8d14 in vtkOpenGLPolyDataMapper::RenderPiece(vtkRenderer*, vtkActor*) () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#14 0x00007fffefef8c63 in vtkPolyDataMapper::Render(vtkRenderer*, vtkActor*) () at /lib/x86_64-linux-gnu/libvtkRenderingCore-7.1.so.7.1p
#15 0x00007fffefe49345 in vtkDataSetMapper::Render(vtkRenderer*, vtkActor*) () at /lib/x86_64-linux-gnu/libvtkRenderingCore-7.1.so.7.1p
#16 0x00007ffff01ed677 in vtkOpenGLActor::Render(vtkRenderer*, vtkMapper*) () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#17 0x00007ffff0439220 in vtkLODActor::Render(vtkRenderer*, vtkMapper*) () at /lib/x86_64-linux-gnu/libvtkRenderingLOD-7.1.so.7.1p
#18 0x00007ffff0438762 in vtkLODActor::RenderOpaqueGeometry(vtkViewport*) () at /lib/x86_64-linux-gnu/libvtkRenderingLOD-7.1.so.7.1p
#19 0x00007fffeff1558b in vtkRenderer::UpdateOpaquePolygonalGeometry() () at /lib/x86_64-linux-gnu/libvtkRenderingCore-7.1.so.7.1p
#20 0x00007ffff02d8fb8 in vtkOpenGLRenderer::DeviceRenderOpaqueGeometry() () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#21 0x00007ffff02d69a6 in vtkOpenGLRenderer::UpdateGeometry() () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#22 0x00007ffff02d6185 in vtkOpenGLRenderer::DeviceRender() () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#23 0x00007fffeff1bc63 in vtkRenderer::Render() () at /lib/x86_64-linux-gnu/libvtkRenderingCore-7.1.so.7.1p
#24 0x00007fffeff14968 in vtkRendererCollection::Render() () at /lib/x86_64-linux-gnu/libvtkRenderingCore-7.1.so.7.1p
#25 0x00007ffff2d7d952 in pcl::visualization::PCLVisualizerInteractorStyle::OnTimer() () at /lib/x86_64-linux-gnu/libpcl_visualization.so.1.10
#26 0x00007fffeff94400 in vtkInteractorStyle::ProcessEvents(vtkObject*, unsigned long, void*, void*) () at /lib/x86_64-linux-gnu/libvtkRenderingCore-7.1.so.7.1p
#27 0x00007fffef56f08d in vtkCallbackCommand::Execute(vtkObject*, unsigned long, void*) () at /lib/x86_64-linux-gnu/libvtkCommonCore-7.1.so.7.1p
#28 0x00007fffef60e192 in () at /lib/x86_64-linux-gnu/libvtkCommonCore-7.1.so.7.1p
#29 0x00007ffff0386cb2 in vtkXRenderWindowInteractorTimer(void*, unsigned long*) () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#30 0x00007fffe972360e in () at /lib/x86_64-linux-gnu/libXt.so.6
#31 0x00007fffe9724227 in XtAppNextEvent () at /lib/x86_64-linux-gnu/libXt.so.6
#32 0x00007ffff038603c in vtkXRenderWindowInteractor::StartEventLoop() () at /lib/x86_64-linux-gnu/libvtkRenderingOpenGL2-7.1.so.7.1p
#33 0x00007ffff2db8e0a in pcl::visualization::PCLVisualizer::spinOnce(int, bool) () at /lib/x86_64-linux-gnu/libpcl_visualization.so.1.10
#34 0x00005555555cfa61 in lo::MapViewer<pcl::PointXYZINormal>::judge_pause(boost::shared_ptr<pcl::visualization::PCLVisualizer>&, int) (display_time_ms=<optimized out>, viewer=..., this=0x7fffffffc490)
at /home/markus/Repos/MULLS/include/common/map_viewer.h:108
#35 lo::MapViewer<pcl::PointXYZINormal>::judge_pause(boost::shared_ptr<pcl::visualization::PCLVisualizer>&, int) (this=0x7fffffffc490, viewer=..., display_time_ms=<optimized out>)
--Type <RET> for more, q to quit, c to continue without paging--c
MULLS/include/common/map_viewer.h:108
#36 0x000055555560d42b in lo::MapViewer<pcl::PointXYZINormal>::display_lo_realtime(boost::shared_ptr<lo::cloudblock_t>&, boost::shared_ptr<pcl::visualization::PCLVisualizer>&, int, int, int) (this=0x7fffffffc490, current_frame=..., viewer=..., display_time_ms=1, display_downsample_ratio_current=<optimized out>, display_downsample_ratio_history=<optimized out>) at /usr/include/boost/smart_ptr/detail/shared_count.hpp:122
#37 0x00005555555a4f37 in main(int, char**) (argc=<optimized out>, argv=<optimized out>) at /home/markus/Repos/MULLS/test/mulls_slam.cpp:745
A common pattern in MULLS is to build instances of
pcl::PointCloud
by appending points directly into the underlying vectorpoints
using->points.push_back
.This leaves the object in an invalid state, as the member attributes
pcl::PointCloud::width
andheight
are out-of-sync with the actual size. This can especially cause problems when passing such an object to an external library, as is the case with the map viewer.Please consider using
pcl::PointCloud.push_back
instead ofpcl::PointCloud::points.push_back
.This issue might be part of the reason for a program crash I am experiencing while having the map viewer enabled:
GDB stacktrace
This may also be related to #18 (comment)
The text was updated successfully, but these errors were encountered: