Skip to content

Commit

Permalink
Use uint64_t with gazebo-entity user dataa (#1451)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <ahcorde@gmail.com>
  • Loading branch information
ahcorde authored May 4, 2022
1 parent 7063d41 commit 9370793
Show file tree
Hide file tree
Showing 10 changed files with 47 additions and 53 deletions.
3 changes: 1 addition & 2 deletions src/gui/plugins/align_tool/AlignTool.cc
Original file line number Diff line number Diff line change
Expand Up @@ -365,8 +365,7 @@ void AlignTool::Align()
continue;

if (vis->HasUserData("gazebo-entity") &&
std::get<int>(vis->UserData("gazebo-entity")) ==
static_cast<int>(entityId))
std::get<uint64_t>(vis->UserData("gazebo-entity")) == entityId)
{
// Check here to see if visual is top level or not, continue if not
auto topLevelVis = this->TopLevelVisual(this->dataPtr->scene, vis);
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 @@ -1029,7 +1029,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->dataPtr->renderUtil.ViewTransparent(targetEntity);
}
else
Expand All @@ -1055,7 +1055,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->dataPtr->renderUtil.ViewCOM(targetEntity);
}
else
Expand All @@ -1081,7 +1081,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->dataPtr->renderUtil.ViewInertia(targetEntity);
}
else
Expand All @@ -1107,7 +1107,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->dataPtr->renderUtil.ViewJoints(targetEntity);
}
else
Expand All @@ -1133,7 +1133,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->dataPtr->renderUtil.ViewWireframes(targetEntity);
}
else
Expand All @@ -1159,7 +1159,7 @@ void IgnRenderer::Render(RenderSync *_renderSync)
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->dataPtr->renderUtil.ViewCollisions(targetEntity);
}
else
Expand Down
13 changes: 7 additions & 6 deletions src/gui/plugins/select_entities/SelectEntities.cc
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,8 @@ void SelectEntitiesPrivate::HandleEntitySelection()
Entity entityId = kNullEntity;
try
{
entityId = std::get<int>(visualToHighLight->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(
visualToHighLight->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &_e)
{
Expand Down Expand Up @@ -213,7 +214,7 @@ void SelectEntitiesPrivate::HandleEntitySelection()
Entity entityId = kNullEntity;
try
{
entityId = std::get<int>(visual->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &e)
{
Expand Down Expand Up @@ -244,7 +245,7 @@ void SelectEntitiesPrivate::LowlightNode(const rendering::VisualPtr &_visual)
{
try
{
entityId = std::get<int>(_visual->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(_visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &)
{
Expand Down Expand Up @@ -272,7 +273,7 @@ void SelectEntitiesPrivate::HighlightNode(const rendering::VisualPtr &_visual)
Entity entityId = kNullEntity;
try
{
entityId = std::get<int>(_visual->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(_visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &)
{
Expand Down Expand Up @@ -359,7 +360,7 @@ void SelectEntitiesPrivate::SetSelectedEntity(
{
try
{
entityId = std::get<int>(topLevelVisual->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(topLevelVisual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &)
{
Expand Down Expand Up @@ -545,7 +546,7 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event)
Entity entityId = kNullEntity;
try
{
entityId = std::get<int>(visual->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &)
{
Expand Down
3 changes: 1 addition & 2 deletions src/gui/plugins/transform_control/TransformControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -801,8 +801,7 @@ void TransformControlPrivate::HandleTransform()
auto entityId = kNullEntity;
try
{
entityId = static_cast<unsigned int>(
std::get<int>(visual->UserData("gazebo-entity")));
entityId = std::get<uint64_t>(visual->UserData("gazebo-entity"));
}
catch (std::bad_variant_access &)
{
Expand Down
3 changes: 1 addition & 2 deletions src/gui/plugins/view_angle/ViewAngle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -377,8 +377,7 @@ void ViewAnglePrivate::OnRender()

try
{
if (std::get<int>(vis->UserData("gazebo-entity")) !=
static_cast<int>(entity))
if (std::get<uint64_t>(vis->UserData("gazebo-entity")) != entity)
{
continue;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -806,7 +806,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->ViewCOM(targetEntity);
}
else
Expand All @@ -832,7 +832,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->ViewInertia(targetEntity);
}
else
Expand All @@ -858,7 +858,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->ViewTransparent(targetEntity);
}
else
Expand All @@ -884,7 +884,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->ViewCollisions(targetEntity);
}
else
Expand All @@ -910,7 +910,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->ViewJoints(targetEntity);
}
else
Expand All @@ -936,7 +936,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->ViewWireframes(targetEntity);
}
else
Expand All @@ -961,7 +961,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
if (targetVis && targetVis->HasUserData("gazebo-entity"))
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
std::get<uint64_t>(targetVis->UserData("gazebo-entity"));
this->ViewFrames(targetEntity);
}
else
Expand Down Expand Up @@ -1087,7 +1087,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateJointVisual(

rendering::VisualPtr jointVis =
std::dynamic_pointer_cast<rendering::Visual>(jointVisual);
jointVis->SetUserData("gazebo-entity", static_cast<int>(_id));
jointVis->SetUserData("gazebo-entity", _id);
jointVis->SetUserData("pause-update", static_cast<int>(0));
jointVis->SetUserData("gui-only", static_cast<bool>(true));
jointVis->SetLocalPose(_joint.RawPose());
Expand Down Expand Up @@ -1132,7 +1132,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateInertiaVisual(

rendering::VisualPtr inertiaVis =
std::dynamic_pointer_cast<rendering::Visual>(inertiaVisual);
inertiaVis->SetUserData("gazebo-entity", static_cast<int>(_id));
inertiaVis->SetUserData("gazebo-entity", _id);
inertiaVis->SetUserData("pause-update", static_cast<int>(0));
inertiaVis->SetUserData("gui-only", static_cast<bool>(true));
this->visuals[_id] = inertiaVis;
Expand Down Expand Up @@ -1487,7 +1487,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateCollisionVisual(
return vis;
}
rendering::VisualPtr visualVis = this->scene->CreateVisual(name);
visualVis->SetUserData("gazebo-entity", static_cast<int>(_id));
visualVis->SetUserData("gazebo-entity", _id);
visualVis->SetUserData("pause-update", static_cast<int>(0));
visualVis->SetLocalPose(_visual.RawPose());

Expand Down Expand Up @@ -1611,7 +1611,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateCOMVisual(

rendering::VisualPtr comVis =
std::dynamic_pointer_cast<rendering::Visual>(comVisual);
comVis->SetUserData("gazebo-entity", static_cast<int>(_id));
comVis->SetUserData("gazebo-entity", _id);
comVis->SetUserData("pause-update", static_cast<int>(0));
comVis->SetUserData("gui-only", static_cast<bool>(true));
this->visuals[_id] = comVis;
Expand Down Expand Up @@ -1682,7 +1682,8 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::VisualByEntity(

try
{
Entity visualEntity = std::get<int>(visual->UserData("gazebo-entity"));
Entity visualEntity = std::get<uint64_t>(
visual->UserData("gazebo-entity"));

if (visualEntity == _entity)
{
Expand Down
8 changes: 4 additions & 4 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1277,7 +1277,7 @@ void RenderUtil::Update()
// this functionality is needed for temporal placement of a
// visual such as an align preview
updateNode = std::get<int>(vis->UserData("pause-update"));
entityId = std::get<int>(vis->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(vis->UserData("gazebo-entity"));
}
if ((this->dataPtr->transformActive &&
(pose.first == this->dataPtr->selectedEntities.back() ||
Expand Down Expand Up @@ -2690,7 +2690,7 @@ void RenderUtil::SetSelectedEntity(const rendering::NodePtr &_node)
Entity entityId = kNullEntity;

if (vis)
entityId = std::get<int>(vis->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(vis->UserData("gazebo-entity"));

if (entityId == kNullEntity)
return;
Expand Down Expand Up @@ -2750,7 +2750,7 @@ void RenderUtilPrivate::HighlightNode(const rendering::NodePtr &_node)
auto vis = std::dynamic_pointer_cast<rendering::Visual>(_node);
Entity entityId = kNullEntity;
if (vis)
entityId = std::get<int>(vis->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(vis->UserData("gazebo-entity"));
// If the entity is not found in the existing map, create a wire box
auto wireBoxIt = this->wireBoxes.find(entityId);
if (wireBoxIt == this->wireBoxes.end())
Expand Down Expand Up @@ -2808,7 +2808,7 @@ void RenderUtilPrivate::LowlightNode(const rendering::NodePtr &_node)
auto vis = std::dynamic_pointer_cast<rendering::Visual>(_node);
Entity entityId = kNullEntity;
if (vis)
entityId = std::get<int>(vis->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(vis->UserData("gazebo-entity"));
if (this->wireBoxes.find(entityId) != this->wireBoxes.end())
{
ignition::rendering::WireBoxPtr wireBox =
Expand Down
24 changes: 11 additions & 13 deletions src/rendering/SceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -195,8 +195,7 @@ rendering::VisualPtr SceneManager::CreateModel(Entity _id,

rendering::VisualPtr modelVis = this->dataPtr->scene->CreateVisual(name);

// \todo(anyone) change to uint64_t once UserData supports this type
modelVis->SetUserData("gazebo-entity", static_cast<int>(_id));
modelVis->SetUserData("gazebo-entity", _id);
modelVis->SetUserData("pause-update", static_cast<int>(0));
modelVis->SetLocalPose(_model.RawPose());
this->dataPtr->visuals[_id] = modelVis;
Expand Down Expand Up @@ -241,7 +240,7 @@ rendering::VisualPtr SceneManager::CreateLink(Entity _id,
if (parent)
name = parent->Name() + "::" + name;
rendering::VisualPtr linkVis = this->dataPtr->scene->CreateVisual(name);
linkVis->SetUserData("gazebo-entity", static_cast<int>(_id));
linkVis->SetUserData("gazebo-entity", _id);
linkVis->SetUserData("pause-update", static_cast<int>(0));
linkVis->SetLocalPose(_link.RawPose());
this->dataPtr->visuals[_id] = linkVis;
Expand Down Expand Up @@ -287,7 +286,7 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id,
if (parent)
name = parent->Name() + "::" + name;
rendering::VisualPtr visualVis = this->dataPtr->scene->CreateVisual(name);
visualVis->SetUserData("gazebo-entity", static_cast<int>(_id));
visualVis->SetUserData("gazebo-entity", _id);
visualVis->SetUserData("pause-update", static_cast<int>(0));
visualVis->SetLocalPose(_visual.RawPose());

Expand Down Expand Up @@ -548,7 +547,7 @@ std::pair<rendering::VisualPtr, std::vector<Entity>> SceneManager::CopyVisual(
}

this->dataPtr->visuals[childId] = childVisual;
childVisual->SetUserData("gazebo-entity", static_cast<int>(childId));
childVisual->SetUserData("gazebo-entity", childId);
childVisual->SetUserData("pause-update", static_cast<int>(0));
childVisualIds.push_back(childId);

Expand All @@ -564,7 +563,7 @@ std::pair<rendering::VisualPtr, std::vector<Entity>> SceneManager::CopyVisual(
}
else
{
clonedVisual->SetUserData("gazebo-entity", static_cast<int>(_id));
clonedVisual->SetUserData("gazebo-entity", _id);
clonedVisual->SetUserData("pause-update", static_cast<int>(0));

result = {clonedVisual, std::move(childVisualIds)};
Expand Down Expand Up @@ -1201,7 +1200,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id,
rendering::VisualPtr actorVisual = this->dataPtr->scene->CreateVisual(name);
actorVisual->SetLocalPose(_actor.RawPose());
actorVisual->AddGeometry(actorMesh);
actorVisual->SetUserData("gazebo-entity", static_cast<int>(_id));
actorVisual->SetUserData("gazebo-entity", _id);
actorVisual->SetUserData("pause-update", static_cast<int>(0));

this->dataPtr->visuals[_id] = actorVisual;
Expand Down Expand Up @@ -1274,7 +1273,7 @@ rendering::VisualPtr SceneManager::CreateLightVisual(Entity _id,

rendering::VisualPtr lightVis = std::dynamic_pointer_cast<rendering::Visual>(
lightVisual);
lightVis->SetUserData("gazebo-entity", static_cast<int>(_id));
lightVis->SetUserData("gazebo-entity", _id);
lightVis->SetUserData("pause-update", static_cast<int>(0));
this->dataPtr->visuals[_id] = lightVis;

Expand Down Expand Up @@ -1408,7 +1407,7 @@ rendering::VisualPtr SceneManager::CreateInertiaVisual(Entity _id,

rendering::VisualPtr inertiaVis =
std::dynamic_pointer_cast<rendering::Visual>(inertiaVisual);
inertiaVis->SetUserData("gazebo-entity", static_cast<int>(_id));
inertiaVis->SetUserData("gazebo-entity", _id);
inertiaVis->SetUserData("pause-update", static_cast<int>(0));
inertiaVis->SetUserData("gui-only", static_cast<bool>(true));
this->dataPtr->visuals[_id] = inertiaVis;
Expand Down Expand Up @@ -1541,7 +1540,7 @@ rendering::VisualPtr SceneManager::CreateJointVisual(

rendering::VisualPtr jointVis =
std::dynamic_pointer_cast<rendering::Visual>(jointVisual);
jointVis->SetUserData("gazebo-entity", static_cast<int>(_id));
jointVis->SetUserData("gazebo-entity", _id);
jointVis->SetUserData("pause-update", static_cast<int>(0));
jointVis->SetUserData("gui-only", static_cast<bool>(true));
jointVis->SetLocalPose(_joint.RawPose());
Expand Down Expand Up @@ -1590,7 +1589,7 @@ rendering::VisualPtr SceneManager::CreateCOMVisual(Entity _id,

rendering::VisualPtr comVis =
std::dynamic_pointer_cast<rendering::Visual>(comVisual);
comVis->SetUserData("gazebo-entity", static_cast<int>(_id));
comVis->SetUserData("gazebo-entity", _id);
comVis->SetUserData("pause-update", static_cast<int>(0));
comVis->SetUserData("gui-only", static_cast<bool>(true));
this->dataPtr->visuals[_id] = comVis;
Expand Down Expand Up @@ -1803,8 +1802,7 @@ bool SceneManager::AddSensor(Entity _gazeboId, const std::string &_sensorName,
return false;
}

// \todo(anyone) change to uint64_t once UserData supports this type
sensor->SetUserData("gazebo-entity", static_cast<int>(_gazeboId));
sensor->SetUserData("gazebo-entity", _gazeboId);

if (parent)
{
Expand Down
6 changes: 2 additions & 4 deletions src/systems/shader_param/ShaderParam.cc
Original file line number Diff line number Diff line change
Expand Up @@ -284,11 +284,9 @@ void ShaderParamPrivate::OnUpdate()
nodes.pop_front();
if (n && n->HasUserData("gazebo-entity"))
{
// RenderUti stores gazebo-entity user data as int
// \todo(anyone) Change this to uint64_t in Ignition H?
auto variant = n->UserData("gazebo-entity");
const int *value = std::get_if<int>(&variant);
if (value && *value == static_cast<int>(this->entity))
const uint64_t *value = std::get_if<uint64_t>(&variant);
if (value && *value == this->entity)
{
this->visual = std::dynamic_pointer_cast<rendering::Visual>(n);
break;
Expand Down
Loading

0 comments on commit 9370793

Please sign in to comment.