Skip to content

Commit

Permalink
Better use of std::variant
Browse files Browse the repository at this point in the history
Signed-off-by: Maksim Derbasov <[email protected]>
  • Loading branch information
ntfshard committed Jan 12, 2025
1 parent d83d135 commit 8663bbb
Show file tree
Hide file tree
Showing 20 changed files with 54 additions and 85 deletions.
2 changes: 1 addition & 1 deletion examples/worlds/ackermann_steering.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@
</link>

<link name='front_right_wheel'>
<pose>0.554282 -0.625029 -0.025 -1.5707 0 0</pose>
<pose>0.554283 -0.625029 -0.025 -1.5707 0 0</pose>
<inertial>
<mass>2</mass>
<inertia>
Expand Down
12 changes: 6 additions & 6 deletions src/SystemLoader.cc
Original file line number Diff line number Diff line change
Expand Up @@ -75,14 +75,14 @@ class gz::sim::SystemLoaderPrivate
<< "]. Using [" << filename << "] instead." << std::endl;
}

std::list<std::string> paths = this->PluginPaths();
const std::list<std::string> paths = this->PluginPaths();
common::SystemPaths systemPaths;
for (const auto &p : paths)
{
systemPaths.AddPluginPaths(p);
}

auto pathToLib = systemPaths.FindSharedLibrary(filename);
const auto pathToLib = systemPaths.FindSharedLibrary(filename);
if (pathToLib.empty())
{
// We assume gz::sim corresponds to the levels feature
Expand All @@ -94,7 +94,7 @@ class gz::sim::SystemLoaderPrivate
return false;
}

auto pluginNames = this->loader.LoadLib(pathToLib, true);
const auto pluginNames = this->loader.LoadLib(pathToLib, true);
if (pluginNames.empty())
{
std::stringstream ss;
Expand All @@ -107,7 +107,7 @@ class gz::sim::SystemLoaderPrivate
return false;
}

auto pluginName = *pluginNames.begin();
const auto &pluginName = *pluginNames.begin();
if (pluginName.empty())
{
std::stringstream ss;
Expand Down Expand Up @@ -200,7 +200,7 @@ class gz::sim::SystemLoaderPrivate
// Default plugin search path environment variable
public: std::string pluginPathEnv{"GZ_SIM_SYSTEM_PLUGIN_PATH"};

/// \brief Plugin loader instace
/// \brief Plugin loader instance
public: gz::plugin::Loader loader;

/// \brief Paths to search for system plugins.
Expand Down Expand Up @@ -232,7 +232,7 @@ void SystemLoader::AddSystemPluginPath(const std::string &_path)
std::optional<SystemPluginPtr> SystemLoader::LoadPlugin(
const sdf::Plugin &_plugin)
{
if (_plugin.Filename() == "")
if (_plugin.Filename().empty())
{
gzerr << "Failed to instantiate system plugin: empty argument "
"[(filename): " << _plugin.Filename() << "] " << std::endl;
Expand Down
4 changes: 2 additions & 2 deletions src/gui/plugins/apply_force_torque/ApplyForceTorque.cc
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ void ApplyForceTorque::LoadConfig(const tinyxml2::XMLElement */*_pluginElem*/)
this->dataPtr->worldName = worldNames[0].toStdString();
auto topic = transport::TopicUtils::AsValidTopic(
"/world/" + this->dataPtr->worldName + "/wrench");
if (topic == "")
if (topic.empty())
{
gzerr << "Unable to create publisher" << std::endl;
return;
Expand Down Expand Up @@ -764,7 +764,7 @@ void ApplyForceTorquePrivate::UpdateVisuals()
// https://github.com/gazebosim/gz-rendering/pull/882

// Update gizmo visual rotation so that they are always facing the
// eye position and alligned with the active vector
// eye position and aligned with the active vector
math::Quaterniond gizmoRot = this->linkWorldPose.Rot() * this->vectorRot;
math::Vector3d eye = gizmoRot.RotateVectorReverse(
(this->camera->WorldPosition() - pos).Normalized());
Expand Down
2 changes: 1 addition & 1 deletion src/gui/plugins/component_inspector/ComponentInspector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -967,7 +967,7 @@ bool ComponentInspector::eventFilter(QObject *_obj, QEvent *_event)
auto event = reinterpret_cast<gui::events::EntitiesSelected *>(_event);
if (event && !event->Data().empty())
{
this->SetEntity(*event->Data().begin());
this->SetEntity(event->Data().front());

Check warning on line 970 in src/gui/plugins/component_inspector/ComponentInspector.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/component_inspector/ComponentInspector.cc#L970

Added line #L970 was not covered by tests
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1014,7 +1014,7 @@ bool ComponentInspectorEditor::eventFilter(QObject *_obj, QEvent *_event)
auto event = reinterpret_cast<gui::events::EntitiesSelected *>(_event);
if (event && !event->Data().empty())
{
this->SetEntity(*event->Data().begin());
this->SetEntity(event->Data().front());
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -315,7 +315,7 @@ bool JointPositionController::eventFilter(QObject *_obj, QEvent *_event)
auto event = reinterpret_cast<gui::events::EntitiesSelected *>(_event);
if (event && !event->Data().empty())
{
this->SetModelEntity(*event->Data().begin());
this->SetModelEntity(event->Data().front());

Check warning on line 318 in src/gui/plugins/joint_position_controller/JointPositionController.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/joint_position_controller/JointPositionController.cc#L318

Added line #L318 was not covered by tests
}
}

Expand Down
5 changes: 3 additions & 2 deletions src/gui/plugins/mouse_drag/MouseDrag.cc
Original file line number Diff line number Diff line change
Expand Up @@ -680,12 +680,13 @@ void MouseDragPrivate::HandleMouseEvents()
this->mode = MouseDragMode::NONE;
return;
}
try
if (std::holds_alternative<uint64_t>(
visual->Parent()->UserData("gazebo-entity")))
{
this->linkId =
std::get<uint64_t>(visual->Parent()->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &e)
else
{
this->mode = MouseDragMode::NONE;
return;
Expand Down
2 changes: 1 addition & 1 deletion src/gui/plugins/playback_scrubber/PlaybackScrubber.cc
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ void PlaybackScrubber::Update(const UpdateInfo &_info,
}

// Populate the world name
if (this->dataPtr->worldName == "")
if (this->dataPtr->worldName.empty())
{
// TODO(anyone) Only one world is supported for now
auto worldNames = gz::gui::worldNames();
Expand Down
2 changes: 1 addition & 1 deletion src/gui/plugins/plot_3d/Plot3D.cc
Original file line number Diff line number Diff line change
Expand Up @@ -270,7 +270,7 @@ bool Plot3D::eventFilter(QObject *_obj, QEvent *_event)
auto event = reinterpret_cast<gui::events::EntitiesSelected *>(_event);
if (event && !event->Data().empty())
{
this->SetTargetEntity(*event->Data().begin());
this->SetTargetEntity(event->Data().front());

Check warning on line 273 in src/gui/plugins/plot_3d/Plot3D.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/plot_3d/Plot3D.cc#L273

Added line #L273 was not covered by tests
}
}

Expand Down
4 changes: 2 additions & 2 deletions src/gui/plugins/resource_spawner/ResourceSpawner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ namespace gz::sim
public: std::vector<fuel_tools::ServerConfig> servers;

/// \brief Data structure to hold relevant bits for a worker thread that
/// fetches the list of recources available for an owner on Fuel.
/// fetches the list of resources available for an owner on Fuel.
struct FetchResourceListWorker
{
/// \brief Thread that runs the worker
Expand Down Expand Up @@ -441,7 +441,7 @@ bool compareByDownloaded(const Resource &a, const Resource &b)
/////////////////////////////////////////////////
void ResourceSpawner::FilterResources(std::vector<Resource> &_resources)
{
if (this->dataPtr->displayData.searchKeyword == "")
if (this->dataPtr->displayData.searchKeyword.empty())
return;

std::string searchKeyword = this->dataPtr->displayData.searchKeyword;
Expand Down
39 changes: 9 additions & 30 deletions src/gui/plugins/select_entities/SelectEntities.cc
Original file line number Diff line number Diff line change
Expand Up @@ -171,15 +171,12 @@ void SelectEntitiesPrivate::HandleEntitySelection()
this->selectedEntitiesID.push_back(this->selectedEntitiesIDNew[i]);

Entity entityId = kNullEntity;
try
if (std::holds_alternative<uint64_t>(
visualToHighLight->UserData("gazebo-entity")))

Check warning on line 175 in src/gui/plugins/select_entities/SelectEntities.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/select_entities/SelectEntities.cc#L174-L175

Added lines #L174 - L175 were not covered by tests
{
entityId = std::get<uint64_t>(
visualToHighLight->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &_e)
{
// It's ok to get here
}

this->selectedEntities.push_back(entityId);

Expand Down Expand Up @@ -212,14 +209,10 @@ void SelectEntitiesPrivate::HandleEntitySelection()
}

Entity entityId = kNullEntity;
try
if (std::holds_alternative<uint64_t>(visual->UserData("gazebo-entity")))

Check warning on line 212 in src/gui/plugins/select_entities/SelectEntities.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/select_entities/SelectEntities.cc#L212

Added line #L212 was not covered by tests
{
entityId = std::get<uint64_t>(visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &e)
{
// It's ok to get here
}

this->selectionHelper.selectEntity = entityId;

Expand All @@ -243,14 +236,10 @@ void SelectEntitiesPrivate::LowlightNode(const rendering::VisualPtr &_visual)
Entity entityId = kNullEntity;
if (_visual)
{
try
if (std::holds_alternative<uint64_t>(_visual->UserData("gazebo-entity")))

Check warning on line 239 in src/gui/plugins/select_entities/SelectEntities.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/select_entities/SelectEntities.cc#L239

Added line #L239 was not covered by tests
{
entityId = std::get<uint64_t>(_visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &)
{
// It's ok to get here
}
}
if (this->wireBoxes.find(entityId) != this->wireBoxes.end())
{
Expand All @@ -271,14 +260,10 @@ void SelectEntitiesPrivate::HighlightNode(const rendering::VisualPtr &_visual)
}

Entity entityId = kNullEntity;
try
if (std::holds_alternative<uint64_t>(_visual->UserData("gazebo-entity")))

Check warning on line 263 in src/gui/plugins/select_entities/SelectEntities.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/select_entities/SelectEntities.cc#L263

Added line #L263 was not covered by tests
{
entityId = std::get<uint64_t>(_visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &)
{
// It's ok to get here
}

// If the entity is not found in the existing map, create a wire box
auto wireBoxIt = this->wireBoxes.find(entityId);
Expand Down Expand Up @@ -358,14 +343,11 @@ void SelectEntitiesPrivate::SetSelectedEntity(

if (topLevelVisual)
{
try
if (std::holds_alternative<uint64_t>(
topLevelVisual->UserData("gazebo-entity")))

Check warning on line 347 in src/gui/plugins/select_entities/SelectEntities.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/select_entities/SelectEntities.cc#L346-L347

Added lines #L346 - L347 were not covered by tests
{
entityId = std::get<uint64_t>(topLevelVisual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &)
{
// It's ok to get here
}
}

if (entityId == kNullEntity)
Expand Down Expand Up @@ -544,14 +526,11 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event)
auto visual = this->dataPtr->scene->VisualByIndex(i);

Entity entityId = kNullEntity;
try
if (std::holds_alternative<uint64_t>(
visual->UserData("gazebo-entity")))

Check warning on line 530 in src/gui/plugins/select_entities/SelectEntities.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/select_entities/SelectEntities.cc#L529-L530

Added lines #L529 - L530 were not covered by tests
{
entityId = std::get<uint64_t>(visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &)
{
// It's ok to get here
}

if (entityId == entity)
{
Expand Down
9 changes: 3 additions & 6 deletions src/gui/plugins/transform_control/TransformControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -712,7 +712,8 @@ void TransformControlPrivate::HandleMouseEvents()
{
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(1));
} catch (std::bad_variant_access &)
}
catch (std::bad_variant_access &)

Check warning on line 716 in src/gui/plugins/transform_control/TransformControl.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/transform_control/TransformControl.cc#L716

Added line #L716 was not covered by tests
{
// It's ok to get here
}
Expand Down Expand Up @@ -744,14 +745,10 @@ void TransformControlPrivate::HandleMouseEvents()
{
auto visual = this->scene->VisualByIndex(i);
auto entityId = kNullEntity;
try
if (std::holds_alternative<uint64_t>(visual->UserData("gazebo-entity")))

Check warning on line 748 in src/gui/plugins/transform_control/TransformControl.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/transform_control/TransformControl.cc#L748

Added line #L748 was not covered by tests
{
entityId = std::get<uint64_t>(visual->UserData("gazebo-entity"));
}
catch (std::bad_variant_access &)
{
// It's ok to get here
}
if (entityId == nodeId)
{
target = std::dynamic_pointer_cast<rendering::Node>(
Expand Down
16 changes: 7 additions & 9 deletions src/gui/plugins/view_angle/ViewAngle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -336,11 +336,12 @@ bool ViewAngle::OnMoveToModelService(const gz::msgs::GUICamera &_msg,
return false;
}
Entity entityId = kNullEntity;
try
if (std::holds_alternative<uint64_t>(
visualToMove->UserData("gazebo-entity")))
{
entityId = std::get<uint64_t>(visualToMove->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &_e)
else
{
gzerr << "Failed to get gazebo-entity user data ["
<< visualToMove->Name() << "]" << std::endl;
Expand Down Expand Up @@ -452,14 +453,10 @@ void ViewAnglePrivate::OnRender()
if (cam)
{
bool isUserCamera = false;
try
if (std::holds_alternative<bool>(cam->UserData("user-camera")))
{
isUserCamera = std::get<bool>(cam->UserData("user-camera"));
}
catch (std::bad_variant_access &)
{
continue;
}
if (isUserCamera)
{
this->camera = cam;
Expand Down Expand Up @@ -496,14 +493,15 @@ void ViewAnglePrivate::OnRender()
if (!vis)
continue;

try
if (std::holds_alternative<uint64_t>(
vis->UserData("gazebo-entity")))
{
if (std::get<uint64_t>(vis->UserData("gazebo-entity")) != entity)
{
continue;
}
}
catch (std::bad_variant_access &)
else
{
continue;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -562,8 +562,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
// create new wireframe visuals
for (const auto &link : this->newWireframeVisualLinks)
{
std::vector<Entity> visEntities =
this->linkToVisualEntities[link];
const auto &visEntities = this->linkToVisualEntities[link];

Check warning on line 565 in src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc#L565

Added line #L565 was not covered by tests

for (const auto &visEntity : visEntities)
{
Expand Down Expand Up @@ -592,8 +591,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
// create new transparent visuals
for (const auto &link : this->newTransparentVisualLinks)
{
std::vector<Entity> visEntities =
this->linkToVisualEntities[link];
const auto &visEntities = this->linkToVisualEntities[link];

Check warning on line 594 in src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc#L594

Added line #L594 was not covered by tests

for (const auto &visEntity : visEntities)
{
Expand Down Expand Up @@ -1737,7 +1735,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::VisualByEntity(
{
auto visual = this->scene->VisualByIndex(i);

try
if (std::holds_alternative<uint64_t>(visual->UserData("gazebo-entity")))

Check warning on line 1738 in src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc

View check run for this annotation

Codecov / codecov/patch

src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc#L1738

Added line #L1738 was not covered by tests
{
Entity visualEntity = std::get<uint64_t>(
visual->UserData("gazebo-entity"));
Expand All @@ -1747,10 +1745,6 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::VisualByEntity(
return visual;
}
}
catch (std::bad_variant_access &)
{
// It's ok to get here
}
}
return nullptr;
}
Expand Down
2 changes: 1 addition & 1 deletion src/systems/apply_joint_force/ApplyJointForce.cc
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ void ApplyJointForce::Configure(const Entity &_entity,
this->dataPtr->jointName = sdfElem->Get<std::string>();
}

if (this->dataPtr->jointName == "")
if (this->dataPtr->jointName.empty())
{
gzerr << "ApplyJointForce found an empty jointName parameter. "
<< "Failed to initialize.";
Expand Down
2 changes: 1 addition & 1 deletion src/systems/collada_world_exporter/ColladaWorldExporter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@ class gz::sim::systems::ColladaWorldExporterPrivate

const auto subMeshName = _geom->Data().MeshShape()->Submesh();
scale = _geom->Data().MeshShape()->Scale();
if(subMeshName == "")
if (subMeshName.empty())
{
for (unsigned int k = 0; k < mesh->SubMeshCount(); k++)
{
Expand Down
Loading

0 comments on commit 8663bbb

Please sign in to comment.