Hello again.
I decided to take a closer look at ign_rviz. I am trying to add the PoseWithCovariance display in this branch. However, I am encountering some strange behaviour.
I am currently adding a simple covariance visual, with no scalings and offsets yet so I do not need ROS messages to test rendering. The display for now just calls the constructor shown here:
CovarianceVisual::CovarianceVisual(ignition::rendering::VisualPtr parent_node, CovarianceUserData user_data) : user_data_(user_data)
{
this->scene_ = parent_node->Scene();
this->root_visual_ = this->scene_->CreateVisual();
parent_node->AddChild(this->root_visual_);
this->fixed_orientation_visual_ = this->scene_->CreateVisual();
this->root_visual_->AddChild(this->fixed_orientation_visual_);
this->position_root_visual_ = this->scene_->CreateVisual();
if (this->user_data_.position_frame == Frame::Local)
this->root_visual_->AddChild(this->position_root_visual_);
else
this->fixed_orientation_visual_->AddChild(this->position_root_visual_);
this->orientation_root_visual_ = this->scene_->CreateVisual();
if (this->user_data_.orientation_frame == Frame::Local)
this->root_visual_->AddChild(this->orientation_root_visual_);
else
this->fixed_orientation_visual_->AddChild(this->orientation_root_visual_);
this->createMaterials();
this->position_visual_ = this->scene_->CreateVisual();
this->position_visual_->SetInheritScale(false);
this->position_ellipse_ = this->scene_->CreateSphere();
this->position_visual_->AddGeometry(this->position_ellipse_);
this->position_visual_->SetMaterial(this->materials_[kPos], false);
this->position_root_visual_->AddChild(this->position_visual_);
this->position_visual_->SetLocalPosition(1.0 * math::Vector3d::UnitZ);
this->position_visual_->SetLocalRotation(math::Quaterniond(0, 0, 0));
for (int i = 0; i < kNumOrientationShapes; i++) {
// Visual to position and orient the shape along the axis. One for each axis.
this->orientation_visuals_[i] = this->scene_->CreateVisual();
// Does not inherit scale from the parent.
// This is needed to keep the cylinders with the same height.
// The scale is set by setOrientationScale()
this->orientation_visuals_[i]->SetInheritScale(false);
if (i != kYaw2D) {
this->orientation_shapes_[i] = this->scene_->CreateCylinder();
} else {
this->orientation_shapes_[i] = this->scene_->CreateCone(); // TODO: use pie slice instead
}
this->orientation_visuals_[i]->AddGeometry(this->orientation_shapes_[i]);
this->orientation_visuals_[i]->SetMaterial(this->materials_[i+1], false);
this->orientation_root_visual_->AddChild(this->orientation_visuals_[i]);
}
// Position the cylinders at position 1.0 in the respective axis, and perpendicular to the axis.
double offset = user_data_.orientation_offset;
// x-axis (roll)
orientation_visuals_[kRoll]->SetLocalPosition(offset * math::Vector3d::UnitX);
orientation_visuals_[kRoll]->SetLocalRotation(math::Quaterniond(math::Vector3d::UnitY, math::Angle::HalfPi.Radian()));
// y-axis (pitch)
orientation_visuals_[kPitch]->SetLocalPosition(offset * math::Vector3d::UnitY);
orientation_visuals_[kPitch]->SetLocalRotation(math::Quaterniond(math::Vector3d::UnitX, math::Angle::HalfPi.Radian()));
// z-axis (yaw)
orientation_visuals_[kYaw]->SetLocalPosition(offset * math::Vector3d::UnitZ);
orientation_visuals_[kYaw]->SetLocalRotation(math::Quaterniond(0, 0, 0)); // no rotation needed
// z-axis (yaw 2D)
orientation_visuals_[kYaw2D]->SetLocalPosition(cone_origin_to_top * math::Vector3d::UnitX);
orientation_visuals_[kYaw2D]->SetLocalRotation(math::Quaterniond(math::Vector3d::UnitZ, math::Angle::HalfPi.Radian()));
}
I am expecting to see one sphere, 3 cylinders and a cone when adding my display. However I see nothing. What’s perhaps weirder is that when I first add another display that draws something on the screen (e.g. AxesDisplay) before PoseWithCovariance display, something does seem to work. I do see the cylinders and the cone, and I can interact with them using their settings, but never the sphere. Even if I just change the geometries passed to orientation_visuals_
from Cylinder/Cone to Sphere, I can’t get any spheres to be drawn.
I am also getting some unpredictable glitching and crashing. Here is the gdb backtrace:
0x00007fff9e9a8f54 in Ogre::Math::calculateBasicFaceNormalWithoutNormalize(Ogre::Vector3 const&, Ogre::Vector3 const&, Ogre::Vector3 const&) ()
from /lib/x86_64-linux-gnu/libOgreMain.so.1.9.0
(gdb) bt
#0 0x00007fff9e9a8f54 in Ogre::Math::calculateBasicFaceNormalWithoutNormalize(Ogre::Vector3 const&, Ogre::Vector3 const&, Ogre::Vector3 const&) ()
at /lib/x86_64-linux-gnu/libOgreMain.so.1.9.0
#1 0x00007fff9e9a90a5 in Ogre::Math::intersects(Ogre::Ray const&, Ogre::Vector3 const&, Ogre::Vector3 const&, Ogre::Vector3 const&, bool, bool) ()
at /lib/x86_64-linux-gnu/libOgreMain.so.1.9.0
#2 0x00007fff9eedcc3f in ignition::rendering::v6::OgreRayQuery::ClosestPoint() (this=0x7fff64125950)
at /home/thodoris/src/ignition/src/ign-rendering/ogre/src/OgreRayQuery.cc:123
#3 0x00007fffc4f2e415 in ignition::gui::plugins::IgnRenderer::ScreenToScene(ignition::math::v6::Vector2<int> const&) const (this=0x55555634ec80, _screenPos=...)
at /usr/include/c++/9/bits/shared_ptr_base.h:1020
#4 0x00007fffc4f2e5b9 in ignition::gui::plugins::IgnRenderer::BroadcastHoverPos() (this=<optimized out>)
at /home/thodoris/src/ignition/src/ign-gui/src/plugins/scene3d/Scene3D.cc:1039
#5 0x00007fffc4f38516 in ignition::gui::plugins::IgnRenderer::HandleMouseEvent() (this=0x55555634ec80)
at /home/thodoris/src/ignition/src/ign-gui/src/plugins/scene3d/Scene3D.cc:918
#6 0x00007fffc4f38649 in ignition::gui::plugins::IgnRenderer::Render() (this=0x55555634ec80) at /home/thodoris/src/ignition/src/ign-gui/src/plugins/scene3d/Scene3D.cc:901
#7 0x00007fffc4f3954e in ignition::gui::plugins::RenderThread::RenderNext() (this=0x55555634ec40) at /home/thodoris/src/ignition/src/ign-gui/src/plugins/scene3d/Scene3D.cc:1292
#8 0x00007ffff5f5dc2a in QObject::event(QEvent*) () at /lib/x86_64-linux-gnu/libQt5Core.so.5
#9 0x00007ffff694ba66 in QApplicationPrivate::notify_helper(QObject*, QEvent*) () at /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#10 0x00007ffff69550f0 in QApplication::notify(QObject*, QEvent*) () at /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#11 0x00007ffff5f3180a in QCoreApplication::notifyInternal2(QObject*, QEvent*) () at /lib/x86_64-linux-gnu/libQt5Core.so.5
#12 0x00007ffff5f34488 in QCoreApplicationPrivate::sendPostedEvents(QObject*, int, QThreadData*) () at /lib/x86_64-linux-gnu/libQt5Core.so.5
#13 0x00007ffff5f89e37 in () at /lib/x86_64-linux-gnu/libQt5Core.so.5
#14 0x00007ffff42e817d in g_main_context_dispatch () at /lib/x86_64-linux-gnu/libglib-2.0.so.0
#15 0x00007ffff42e8400 in () at /lib/x86_64-linux-gnu/libglib-2.0.so.0
#16 0x00007ffff42e84a3 in g_main_context_iteration () at /lib/x86_64-linux-gnu/libglib-2.0.so.0
#17 0x00007ffff5f89435 in QEventDispatcherGlib::processEvents(QFlags<QEventLoop::ProcessEventsFlag>) () at /lib/x86_64-linux-gnu/libQt5Core.so.5
#18 0x00007ffff5f303ab in QEventLoop::exec(QFlags<QEventLoop::ProcessEventsFlag>) () at /lib/x86_64-linux-gnu/libQt5Core.so.5
#19 0x00007ffff5d68785 in QThread::exec() () at /lib/x86_64-linux-gnu/libQt5Core.so.5
#20 0x00007ffff5d699d2 in () at /lib/x86_64-linux-gnu/libQt5Core.so.5
#21 0x00007ffff6e84609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#22 0x00007ffff59db163 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95
Any clues or better methodology in debugging such cases would be greatly appreciated. Also, regarding node visibility, is it inherited (nodes with at least one invisible parent are invisible regadless of their own value)? And also what is the bit packing of the visibility flags?