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

Rviz crash when using the selection panel on pointcloud2 display with a "decay time" > 0 (0.2) #1537

Closed
reizereyal opened this issue Aug 19, 2020 · 16 comments
Labels

Comments

@reizereyal
Copy link

When adding a pointcloud2 display that displays points on the screen, setting the pointcloud "Decay Time" to a value of 0.2 for example and then using the selection panel to select points for display rviz closes.
Sometime on the first slection bu not always. it may work some time until it crash.
This is not happening if setting the "Decay Time" to 0.

Your environment

  • OS Version: e.g. Ubuntu 18.04
  • ROS Distro: [Melodic]
  • RViz, Qt, OGRE, OpenGl version as printed by rviz:

[ INFO] [1597826165.128561331]: rviz version 1.13.12
[ INFO] [1597826165.128873818]: compiled against Qt version 5.9.5
[ INFO] [1597826165.128921987]: compiled against OGRE version 1.9.0 (Ghadamon)
[ INFO] [1597826165.136671263]: Forcing OpenGl version 0.
[ INFO] [1597826165.408201219]: Stereo is NOT SUPPORTED
[ INFO] [1597826165.408344933]: OpenGl version: 3 (GLSL 1.3).
Gtk-Message: 11:36:26.194: GtkDialog mapped without a transient parent. This is discouraged.
Gtk-Message: 11:42:40.216: GtkDialog mapped without a transient parent. This is discouraged.
rviz: /build/ogre-1.9-B6QkmW/ogre-1.9-1.9.0+dfsg1/OgreMain/include/OgreAxisAlignedBox.h:252: void Ogre::AxisAlignedBox::setExtents(const Ogre::Vector3&, const Ogre::Vector3&): Assertion `(min.x <= max.x && min.y <= max.y && min.z <= max.z) && "The minimum corner of the box must be less than or equal to maximum corner"' failed.
Aborted (core dumped)

@rhaschke
Copy link
Contributor

Is it possible that there are no points left in the selection if you have a small decay time?
Having a backtrace from a debugger would be great. I was not able to reproduce the problem using send_point_cloud_2.py.

@reizereyal
Copy link
Author

Thank you for the prompt reply!!!

Please find below the gdb backtrace of when it crash:

(gdb) bt
#0 0x00007fff7593c6a0 in float rviz::valueFromCloud(boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator > const> const&, unsigned int, unsigned char, unsigned int, unsigned int) ()
at /opt/ros/melodic/lib/librviz_default_plugin.so
#1 0x00007fff75937d1a in rviz::PointCloudSelectionHandler::createProperties(rviz::Picked const&, rviz::Property*) ()
at /opt/ros/melodic/lib/librviz_default_plugin.so
#2 0x00007ffff7b10553 in rviz::SelectionManager::selectionAdded(boost::unordered::unordered_map<unsigned int, rviz::Picked, boost::hash, std::equal_to, std::allocator<std::pair<unsigned int const, rviz::Picked> > > const&) () at /opt/ros/melodic/lib/librviz.so
#3 0x00007ffff7b150bc in rviz::SelectionManager::addSelection(boost::unordered::unordered_map<unsigned int, rviz::Picked, boost::hash, std::equal_to, std::allocator<std::pair<unsigned int const, rviz::Picked> > > const&) () at /opt/ros/melodic/lib/librviz.so
#4 0x00007ffff7b1550c in rviz::SelectionManager::setSelection(boost::unordered::unordered_map<unsigned int, rviz::Picked, boost::hash, std::equal_to, std::allocator<std::pair<unsigned int const, rviz::Picked> > > const&) () at /opt/ros/melodic/lib/librviz.so
#5 0x00007ffff7b15a07 in rviz::SelectionManager::select(Ogre::Viewport*, int, int, int, int, rviz::SelectionManager::SelectType) ()
at /opt/ros/melodic/lib/librviz.so
#6 0x00007fff759dceab in rviz::SelectionTool::processMouseEvent(rviz::ViewportM---Type to continue, or q to quit---
ouseEvent&) () at /opt/ros/melodic/lib/librviz_default_plugin.so
#7 0x00007ffff7b479f0 in rviz::VisualizationManager::handleMouseEvent(rviz::ViewportMouseEvent const&) () at /opt/ros/melodic/lib/librviz.so
#8 0x00007ffff7af9a21 in rviz::RenderPanel::onRenderWindowMouseEvents(QMouseEvent*) () at /opt/ros/melodic/lib/librviz.so
#9 0x00007ffff64cb048 in QWidget::event(QEvent*) ()
at /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5
#10 0x00007ffff648c83c in QApplicationPrivate::notify_helper(QObject*, QEvent*) () at /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5
#11 0x00007ffff649465f in QApplication::notify(QObject*, QEvent*) ()
at /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5
#12 0x00007ffff570e8d8 in QCoreApplication::notifyInternal2(QObject*, QEvent*) () at /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#13 0x00007ffff6493632 in QApplicationPrivate::sendMouseEvent(QWidget*, QMouseEvent*, QWidget*, QWidget*, QWidget**, QPointer&, bool) ()
at /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5
#14 0x00007ffff64e616b in () at /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5
#15 0x00007ffff64e87da in () at /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5
#16 0x00007ffff648c83c in QApplicationPrivate::notify_helper(QObject*, QEvent*) () at /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5
#17 0x00007ffff6494104 in QApplication::notify(QObject*, QEvent*) ()
at /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5
#18 0x00007ffff570e8d8 in QCoreApplication::notifyInternal2(QObject*, QEvent*) (---Type to continue, or q to quit---
) at /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#19 0x00007ffff5cd0583 in QGuiApplicationPrivate::processMouseEvent(QWindowSystemInterfacePrivate::MouseEvent*) () at /usr/lib/x86_64-linux-gnu/libQt5Gui.so.5
#20 0x00007ffff5cd2055 in QGuiApplicationPrivate::processWindowSystemEvent(QWindowSystemInterfacePrivate::WindowSystemEvent*) ()
at /usr/lib/x86_64-linux-gnu/libQt5Gui.so.5
#21 0x00007ffff5ca92eb in QWindowSystemInterface::sendWindowSystemEvents(QFlagsQEventLoop::ProcessEventsFlag) () at /usr/lib/x86_64-linux-gnu/libQt5Gui.so.5
#22 0x00007fffddff4260 in () at /usr/lib/x86_64-linux-gnu/libQt5XcbQpa.so.5
#23 0x00007fffee830417 in g_main_context_dispatch ()
at /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0
#24 0x00007fffee830650 in () at /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0
#25 0x00007fffee8306dc in g_main_context_iteration ()
at /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0
#26 0x00007ffff576788f in QEventDispatcherGlib::processEvents(QFlagsQEventLoop::ProcessEventsFlag) () at /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#27 0x00007ffff570c90a in QEventLoop::exec(QFlagsQEventLoop::ProcessEventsFlag) () at /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#28 0x00007ffff57159b4 in QCoreApplication::exec() ()
at /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#29 0x00005555555af05d in main(int, char**) (argc=1, argv=0x7fffffffda88)
at /home/arbe/workspace/src/arbe_pheonix_radar_Driver/src/arbe_gui/main.cpp:1005
(gdb)

@rhaschke
Copy link
Contributor

Looks like the pointcloud data is deleted before accessing it in valueFromCloud(). As I still can't reproduce the issue, I'm asking you to provide a minimal example to reproduce the problem. Can you reproduce it with the pointcloud generated by send_point_cloud_2.py?

@reizereyal
Copy link
Author

I think I understand the issue, but not sure how to resolve it yet.
I will not be able to reproduce it with send_point_cloud_2.py.

What I am displaying is a high frame rate (15->30FPS) pointcloud coming from an imaging radar.
The pointcloud that is published to rviz using:

	pcl::toROSMsg(cloud,output);
	output.header.frame_id = "image_radar";
	pcl_pub.publish(output);

The problem is that after publishing it when a new frame is received cloud is being cleard:
cloud.clear();

and then filled with new data.
So when I am using a decay_time of lets say 0.2 by the time that it is selected using the mouse it may not be there in the buffer already as new data has was being written to it after it was cleared.

Any idea how I can work around this?
Wouldn't it be wise to add some protection anyway inside valueFromCloud() or similar, just to avoid such a crash?

Best Regards,
Eyal

@rhaschke
Copy link
Contributor

I can try to reproduce this using a higher frame rate in send_point_cloud_2.py.

@rhaschke
Copy link
Contributor

Even with a higher frame rate in send_point_cloud_2.py, I cannot reproduce this. Does your point cloud have any invalid values, e.g. nan or inf?

@reizereyal
Copy link
Author

If this was the case, why can't I reproduce this if I set the decay_time to 0?

@rhaschke
Copy link
Contributor

I'm just looking for possible explanations. Obviously it is somehow related to your data as you cannot reproduce the problem with send_point_cloud_2.py. If you can, I'm happy to take another look.

@reizereyal
Copy link
Author

I am seeing the same issue with:
https://github.com/ros-visualization/rviz/blob/melodic-devel/src/test/send_point_cloud_2.cpp

when I set the rate from
int rate = 1;
to:
int rate = 30;

set a decay time of 0.2, switch to the selection panel and make group selections using the mouse during runtime.
After a couple of time Rviz hangs. sometime with no message and sometimes with this:

arbe@eyal-NUC:~/workspace$ rosrun rviz rviz
[ INFO] [1598043090.511504977]: rviz version 1.13.13
[ INFO] [1598043090.511574170]: compiled against Qt version 5.9.5
[ INFO] [1598043090.511586596]: compiled against OGRE version 1.9.0 (Ghadamon)
[ INFO] [1598043090.515070142]: Forcing OpenGl version 0.
[ INFO] [1598043090.655943627]: Stereo is NOT SUPPORTED
[ INFO] [1598043090.656068681]: OpenGl version: 3 (GLSL 1.3).
rviz: /build/ogre-1.9-B6QkmW/ogre-1.9-1.9.0+dfsg1/OgreMain/include/OgreAxisAlignedBox.h:252: void Ogre::AxisAlignedBox::setExtents(const Ogre::Vector3&, const Ogre::Vector3&): Assertion `(min.x <= max.x && min.y <= max.y && min.z <= max.z) && "The minimum corner of the box must be less than or equal to maximum corner"' failed.

Looks like the same problem I am seeing with my App.

Best Regards,
Eyal

@rhaschke rhaschke added the bug label Aug 25, 2020
@rhaschke
Copy link
Contributor

Thanks. I am able to reproduce the issue with those parameters.

@reizereyal
Copy link
Author

Thank you very much for the update!
Can you please update me in case you find the root cause and have a potential fix?

@rhaschke
Copy link
Contributor

rhaschke commented Mar 4, 2021

I wasn't able to reproduce this on Noetic today. @reizereyal, could you check as well, please?

@reizereyal
Copy link
Author

Sorry for the later reply.
I am still seeing this on Melodic.

my rviz version is the following:

[ INFO] [1616315247.640761789]: rviz version 1.13.16
[ INFO] [1616315247.640818196]: compiled against Qt version 5.9.5
[ INFO] [1616315247.640834621]: compiled against OGRE version 1.9.0 (Ghadamon)

@rhaschke
Copy link
Contributor

Could you try then to build the lastest noetic-devel branch on Melodic?
You will also need the latest of https://github.com/ros-visualization/interactive_markers in your workspace.

@nachumlerner
Copy link

I'm getting this error with gazebo 11 and noetic.
Is there any fix?

gzclient: /build/ogre-1.9-kiU5_5/ogre-1.9-1.9.0+dfsg1/OgreMain/include/OgreAxisAlignedBox.h:251: void Ogre::AxisAlignedBox::setExtents(const Ogre::Vector3&, const Ogre::Vector3&): Assertion `(min.x <= max.x && min.y <= max.y && min.z <= max.z) && "The minimum corner of the box must be less than or equal to maximum corner"' failed.

@rhaschke
Copy link
Contributor

rhaschke commented Aug 6, 2024

@nachumlerner: You seem to have an issue with gzclient, not rviz.
@reizereyal: I'm closing this issue for now. Please feel free to reopen, if your original issue still persists in Melodic.

@rhaschke rhaschke closed this as completed Aug 6, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

No branches or pull requests

3 participants