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

Fix GUI crash when accessing bad rendering UserData #1052

Merged
merged 2 commits into from
Sep 25, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion src/gui/plugins/align_tool/AlignTool.cc
Original file line number Diff line number Diff line change
Expand Up @@ -364,7 +364,8 @@ void AlignTool::Align()
if (!vis)
continue;

if (std::get<int>(vis->UserData("gazebo-entity")) ==
if (vis->HasUserData("gazebo-entity") &&
std::get<int>(vis->UserData("gazebo-entity")) ==
static_cast<int>(entityId))
{
// Check here to see if visual is top level or not, continue if not
Expand Down
16 changes: 7 additions & 9 deletions src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -71,16 +71,14 @@ void EntityContextMenuPrivate::OnRender()
{
auto cam = std::dynamic_pointer_cast<rendering::Camera>(
this->scene->NodeByIndex(i));
if (cam)
if (cam && cam->HasUserData("user-camera") &&
std::get<bool>(cam->UserData("user-camera")))
{
if (std::get<bool>(cam->UserData("user-camera")))
{
this->camera = cam;

igndbg << "Entity context menu plugin is using camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
this->camera = cam;

igndbg << "Entity context menu plugin is using camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
}
}
Expand Down
12 changes: 6 additions & 6 deletions src/gui/plugins/scene3d/Scene3D.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1026,7 +1026,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
scene->NodeByName(this->dataPtr->viewTransparentTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand All @@ -1052,7 +1052,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
scene->NodeByName(this->dataPtr->viewCOMTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand All @@ -1078,7 +1078,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
scene->NodeByName(this->dataPtr->viewInertiaTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand All @@ -1104,7 +1104,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
scene->NodeByName(this->dataPtr->viewJointsTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand All @@ -1130,7 +1130,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
scene->NodeByName(this->dataPtr->viewWireframesTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand All @@ -1156,7 +1156,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
scene->NodeByName(this->dataPtr->viewCollisionsTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand Down
17 changes: 8 additions & 9 deletions src/gui/plugins/select_entities/SelectEntities.cc
Original file line number Diff line number Diff line change
Expand Up @@ -441,15 +441,13 @@ void SelectEntitiesPrivate::Initialize()
{
auto cam = std::dynamic_pointer_cast<rendering::Camera>(
scene->NodeByIndex(i));
if (cam)
if (cam && cam->HasUserData("user-camera") &&
std::get<bool>(cam->UserData("user-camera")))
{
if (std::get<bool>(cam->UserData("user-camera")))
{
this->camera = cam;
igndbg << "TransformControl plugin is using camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
this->camera = cam;
igndbg << "SelectEntities plugin is using camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
}

Expand Down Expand Up @@ -531,7 +529,8 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event)
auto visual = this->dataPtr->scene->VisualByIndex(i);

unsigned int entityId = kNullEntity;
try{
try
{
entityId = std::get<int>(visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &)
Expand Down
18 changes: 8 additions & 10 deletions src/gui/plugins/spawn/Spawn.cc
Original file line number Diff line number Diff line change
Expand Up @@ -311,19 +311,17 @@ void SpawnPrivate::OnRender()
{
auto cam = std::dynamic_pointer_cast<rendering::Camera>(
this->scene->NodeByIndex(i));
if (cam)
if (cam && cam->HasUserData("user-camera") &&
std::get<bool>(cam->UserData("user-camera")))
{
if (std::get<bool>(cam->UserData("user-camera")))
{
this->camera = cam;
this->camera = cam;

// Ray Query
this->rayQuery = this->camera->Scene()->CreateRayQuery();
// Ray Query
this->rayQuery = this->camera->Scene()->CreateRayQuery();

igndbg << "Spawn plugin is using camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
igndbg << "Spawn plugin is using camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
}
}
Expand Down
35 changes: 20 additions & 15 deletions src/gui/plugins/transform_control/TransformControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -507,15 +507,13 @@ void TransformControlPrivate::HandleTransform()
{
auto cam = std::dynamic_pointer_cast<rendering::Camera>(
this->scene->NodeByIndex(i));
if (cam)
if (cam && cam->HasUserData("user-camera") &&
std::get<bool>(cam->UserData("user-camera")))
{
if (std::get<bool>(cam->UserData("user-camera")))
{
this->camera = cam;
igndbg << "TransformControl plugin is using camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
this->camera = cam;
igndbg << "TransformControl plugin is using camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
}

Expand All @@ -534,7 +532,8 @@ void TransformControlPrivate::HandleTransform()
{
if (this->transformControl.Node())
{
try {
try
{
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(0));
}
Expand Down Expand Up @@ -591,7 +590,8 @@ void TransformControlPrivate::HandleTransform()
this->transformControl.SetActiveAxis(axis);
this->transformControl.Start();
if (this->transformControl.Node()){
try {
try
{
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(1));
}
Expand Down Expand Up @@ -623,7 +623,8 @@ void TransformControlPrivate::HandleTransform()
{
if (this->transformControl.Node())
{
try {
try
{
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(0));
}
Expand Down Expand Up @@ -712,7 +713,8 @@ void TransformControlPrivate::HandleTransform()
if (topClickedNode == topClickedVisual)
{
this->transformControl.Attach(topClickedVisual);
try {
try
{
topClickedVisual->SetUserData(
"pause-update", static_cast<int>(1));
}
Expand All @@ -724,7 +726,8 @@ void TransformControlPrivate::HandleTransform()
else
{
this->transformControl.Detach();
try {
try
{
topClickedVisual->SetUserData(
"pause-update", static_cast<int>(0));
}
Expand All @@ -746,7 +749,8 @@ void TransformControlPrivate::HandleTransform()
&& this->transformControl.Active())
{
if (this->transformControl.Node()){
try {
try
{
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(1));
} catch (std::bad_variant_access &)
Expand Down Expand Up @@ -780,7 +784,8 @@ void TransformControlPrivate::HandleTransform()
{
auto visual = this->scene->VisualByIndex(i);
auto entityId = kNullEntity;
try {
try
{
entityId = static_cast<unsigned int>(
std::get<int>(visual->UserData("gazebo-entity")));
}
Expand Down
14 changes: 6 additions & 8 deletions src/gui/plugins/video_recorder/VideoRecorder.cc
Original file line number Diff line number Diff line change
Expand Up @@ -144,15 +144,13 @@ void VideoRecorderPrivate::Initialize()
{
auto cam = std::dynamic_pointer_cast<rendering::Camera>(
this->scene->NodeByIndex(i));
if (cam)
if (cam && cam->HasUserData("user-camera") &&
std::get<bool>(cam->UserData("user-camera")))
{
if (std::get<bool>(cam->UserData("user-camera")))
{
this->camera = cam;
igndbg << "Video Recorder plugin is recoding camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
this->camera = cam;
igndbg << "Video Recorder plugin is recoding camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -690,7 +690,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
scene->NodeByName(this->viewCOMTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand All @@ -716,7 +716,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
scene->NodeByName(this->viewInertiaTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand All @@ -742,7 +742,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
this->scene->VisualByName(this->viewTransparentTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand All @@ -768,7 +768,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
scene->NodeByName(this->viewCollisionsTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand All @@ -794,7 +794,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
scene->NodeByName(this->viewJointsTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand All @@ -820,7 +820,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
scene->NodeByName(this->viewWireframesTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
Expand Down