Skip to content

Commit c72be04

Browse files
authored
Better use of std::variant (#2714)
Signed-off-by: Maksim Derbasov <ntfs.hard@gmail.com>
1 parent d83d135 commit c72be04

File tree

20 files changed

+64
-137
lines changed

20 files changed

+64
-137
lines changed

examples/worlds/ackermann_steering.sdf

+1-1
Original file line numberDiff line numberDiff line change
@@ -221,7 +221,7 @@
221221
</link>
222222

223223
<link name='front_right_wheel'>
224-
<pose>0.554282 -0.625029 -0.025 -1.5707 0 0</pose>
224+
<pose>0.554283 -0.625029 -0.025 -1.5707 0 0</pose>
225225
<inertial>
226226
<mass>2</mass>
227227
<inertia>

src/SystemLoader.cc

+6-6
Original file line numberDiff line numberDiff line change
@@ -75,14 +75,14 @@ class gz::sim::SystemLoaderPrivate
7575
<< "]. Using [" << filename << "] instead." << std::endl;
7676
}
7777

78-
std::list<std::string> paths = this->PluginPaths();
78+
const std::list<std::string> paths = this->PluginPaths();
7979
common::SystemPaths systemPaths;
8080
for (const auto &p : paths)
8181
{
8282
systemPaths.AddPluginPaths(p);
8383
}
8484

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

97-
auto pluginNames = this->loader.LoadLib(pathToLib, true);
97+
const auto pluginNames = this->loader.LoadLib(pathToLib, true);
9898
if (pluginNames.empty())
9999
{
100100
std::stringstream ss;
@@ -107,7 +107,7 @@ class gz::sim::SystemLoaderPrivate
107107
return false;
108108
}
109109

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

203-
/// \brief Plugin loader instace
203+
/// \brief Plugin loader instance
204204
public: gz::plugin::Loader loader;
205205

206206
/// \brief Paths to search for system plugins.
@@ -232,7 +232,7 @@ void SystemLoader::AddSystemPluginPath(const std::string &_path)
232232
std::optional<SystemPluginPtr> SystemLoader::LoadPlugin(
233233
const sdf::Plugin &_plugin)
234234
{
235-
if (_plugin.Filename() == "")
235+
if (_plugin.Filename().empty())
236236
{
237237
gzerr << "Failed to instantiate system plugin: empty argument "
238238
"[(filename): " << _plugin.Filename() << "] " << std::endl;

src/gui/plugins/apply_force_torque/ApplyForceTorque.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -232,7 +232,7 @@ void ApplyForceTorque::LoadConfig(const tinyxml2::XMLElement */*_pluginElem*/)
232232
this->dataPtr->worldName = worldNames[0].toStdString();
233233
auto topic = transport::TopicUtils::AsValidTopic(
234234
"/world/" + this->dataPtr->worldName + "/wrench");
235-
if (topic == "")
235+
if (topic.empty())
236236
{
237237
gzerr << "Unable to create publisher" << std::endl;
238238
return;
@@ -764,7 +764,7 @@ void ApplyForceTorquePrivate::UpdateVisuals()
764764
// https://github.com/gazebosim/gz-rendering/pull/882
765765

766766
// Update gizmo visual rotation so that they are always facing the
767-
// eye position and alligned with the active vector
767+
// eye position and aligned with the active vector
768768
math::Quaterniond gizmoRot = this->linkWorldPose.Rot() * this->vectorRot;
769769
math::Vector3d eye = gizmoRot.RotateVectorReverse(
770770
(this->camera->WorldPosition() - pos).Normalized());

src/gui/plugins/component_inspector/ComponentInspector.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -967,7 +967,7 @@ bool ComponentInspector::eventFilter(QObject *_obj, QEvent *_event)
967967
auto event = reinterpret_cast<gui::events::EntitiesSelected *>(_event);
968968
if (event && !event->Data().empty())
969969
{
970-
this->SetEntity(*event->Data().begin());
970+
this->SetEntity(event->Data().front());
971971
}
972972
}
973973

src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -1014,7 +1014,7 @@ bool ComponentInspectorEditor::eventFilter(QObject *_obj, QEvent *_event)
10141014
auto event = reinterpret_cast<gui::events::EntitiesSelected *>(_event);
10151015
if (event && !event->Data().empty())
10161016
{
1017-
this->SetEntity(*event->Data().begin());
1017+
this->SetEntity(event->Data().front());
10181018
}
10191019
}
10201020

src/gui/plugins/joint_position_controller/JointPositionController.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -315,7 +315,7 @@ bool JointPositionController::eventFilter(QObject *_obj, QEvent *_event)
315315
auto event = reinterpret_cast<gui::events::EntitiesSelected *>(_event);
316316
if (event && !event->Data().empty())
317317
{
318-
this->SetModelEntity(*event->Data().begin());
318+
this->SetModelEntity(event->Data().front());
319319
}
320320
}
321321

src/gui/plugins/mouse_drag/MouseDrag.cc

+3-2
Original file line numberDiff line numberDiff line change
@@ -680,12 +680,13 @@ void MouseDragPrivate::HandleMouseEvents()
680680
this->mode = MouseDragMode::NONE;
681681
return;
682682
}
683-
try
683+
if (std::holds_alternative<uint64_t>(
684+
visual->Parent()->UserData("gazebo-entity")))
684685
{
685686
this->linkId =
686687
std::get<uint64_t>(visual->Parent()->UserData("gazebo-entity"));
687688
}
688-
catch(std::bad_variant_access &e)
689+
else
689690
{
690691
this->mode = MouseDragMode::NONE;
691692
return;

src/gui/plugins/playback_scrubber/PlaybackScrubber.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -145,7 +145,7 @@ void PlaybackScrubber::Update(const UpdateInfo &_info,
145145
}
146146

147147
// Populate the world name
148-
if (this->dataPtr->worldName == "")
148+
if (this->dataPtr->worldName.empty())
149149
{
150150
// TODO(anyone) Only one world is supported for now
151151
auto worldNames = gz::gui::worldNames();

src/gui/plugins/plot_3d/Plot3D.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -270,7 +270,7 @@ bool Plot3D::eventFilter(QObject *_obj, QEvent *_event)
270270
auto event = reinterpret_cast<gui::events::EntitiesSelected *>(_event);
271271
if (event && !event->Data().empty())
272272
{
273-
this->SetTargetEntity(*event->Data().begin());
273+
this->SetTargetEntity(event->Data().front());
274274
}
275275
}
276276

src/gui/plugins/resource_spawner/ResourceSpawner.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,7 @@ namespace gz::sim
8181
public: std::vector<fuel_tools::ServerConfig> servers;
8282

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

447447
std::string searchKeyword = this->dataPtr->displayData.searchKeyword;

src/gui/plugins/select_entities/SelectEntities.cc

+9-30
Original file line numberDiff line numberDiff line change
@@ -171,15 +171,12 @@ void SelectEntitiesPrivate::HandleEntitySelection()
171171
this->selectedEntitiesID.push_back(this->selectedEntitiesIDNew[i]);
172172

173173
Entity entityId = kNullEntity;
174-
try
174+
if (std::holds_alternative<uint64_t>(
175+
visualToHighLight->UserData("gazebo-entity")))
175176
{
176177
entityId = std::get<uint64_t>(
177178
visualToHighLight->UserData("gazebo-entity"));
178179
}
179-
catch(std::bad_variant_access &_e)
180-
{
181-
// It's ok to get here
182-
}
183180

184181
this->selectedEntities.push_back(entityId);
185182

@@ -212,14 +209,10 @@ void SelectEntitiesPrivate::HandleEntitySelection()
212209
}
213210

214211
Entity entityId = kNullEntity;
215-
try
212+
if (std::holds_alternative<uint64_t>(visual->UserData("gazebo-entity")))
216213
{
217214
entityId = std::get<uint64_t>(visual->UserData("gazebo-entity"));
218215
}
219-
catch(std::bad_variant_access &e)
220-
{
221-
// It's ok to get here
222-
}
223216

224217
this->selectionHelper.selectEntity = entityId;
225218

@@ -243,14 +236,10 @@ void SelectEntitiesPrivate::LowlightNode(const rendering::VisualPtr &_visual)
243236
Entity entityId = kNullEntity;
244237
if (_visual)
245238
{
246-
try
239+
if (std::holds_alternative<uint64_t>(_visual->UserData("gazebo-entity")))
247240
{
248241
entityId = std::get<uint64_t>(_visual->UserData("gazebo-entity"));
249242
}
250-
catch(std::bad_variant_access &)
251-
{
252-
// It's ok to get here
253-
}
254243
}
255244
if (this->wireBoxes.find(entityId) != this->wireBoxes.end())
256245
{
@@ -271,14 +260,10 @@ void SelectEntitiesPrivate::HighlightNode(const rendering::VisualPtr &_visual)
271260
}
272261

273262
Entity entityId = kNullEntity;
274-
try
263+
if (std::holds_alternative<uint64_t>(_visual->UserData("gazebo-entity")))
275264
{
276265
entityId = std::get<uint64_t>(_visual->UserData("gazebo-entity"));
277266
}
278-
catch(std::bad_variant_access &)
279-
{
280-
// It's ok to get here
281-
}
282267

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

359344
if (topLevelVisual)
360345
{
361-
try
346+
if (std::holds_alternative<uint64_t>(
347+
topLevelVisual->UserData("gazebo-entity")))
362348
{
363349
entityId = std::get<uint64_t>(topLevelVisual->UserData("gazebo-entity"));
364350
}
365-
catch(std::bad_variant_access &)
366-
{
367-
// It's ok to get here
368-
}
369351
}
370352

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

546528
Entity entityId = kNullEntity;
547-
try
529+
if (std::holds_alternative<uint64_t>(
530+
visual->UserData("gazebo-entity")))
548531
{
549532
entityId = std::get<uint64_t>(visual->UserData("gazebo-entity"));
550533
}
551-
catch(std::bad_variant_access &)
552-
{
553-
// It's ok to get here
554-
}
555534

556535
if (entityId == entity)
557536
{

src/gui/plugins/transform_control/TransformControl.cc

+13-58
Original file line numberDiff line numberDiff line change
@@ -471,15 +471,8 @@ void TransformControlPrivate::HandleTransform()
471471
{
472472
if (this->transformControl.Node())
473473
{
474-
try
475-
{
476-
this->transformControl.Node()->SetUserData(
477-
"pause-update", static_cast<int>(0));
478-
}
479-
catch (std::bad_variant_access &)
480-
{
481-
// It's ok to get here
482-
}
474+
this->transformControl.Node()->SetUserData(
475+
"pause-update", static_cast<int>(0));
483476
}
484477

485478
if (this->transformControl.Active())
@@ -550,15 +543,8 @@ void TransformControlPrivate::HandleMouseEvents()
550543
this->transformControl.Start();
551544
if (this->transformControl.Node())
552545
{
553-
try
554-
{
555-
this->transformControl.Node()->SetUserData(
556-
"pause-update", static_cast<int>(1));
557-
}
558-
catch (std::bad_variant_access &)
559-
{
560-
// It's ok to get here
561-
}
546+
this->transformControl.Node()->SetUserData(
547+
"pause-update", static_cast<int>(1));
562548
}
563549
}
564550
else
@@ -584,15 +570,8 @@ void TransformControlPrivate::HandleMouseEvents()
584570
{
585571
if (this->transformControl.Node())
586572
{
587-
try
588-
{
589-
this->transformControl.Node()->SetUserData(
590-
"pause-update", static_cast<int>(0));
591-
}
592-
catch (std::bad_variant_access &)
593-
{
594-
// It's ok to get here
595-
}
573+
this->transformControl.Node()->SetUserData(
574+
"pause-update", static_cast<int>(0));
596575
}
597576
if (!_result)
598577
gzerr << "Error setting pose" << std::endl;
@@ -673,28 +652,14 @@ void TransformControlPrivate::HandleMouseEvents()
673652
if (topClickedNode == topClickedVisual)
674653
{
675654
this->transformControl.Attach(topClickedVisual);
676-
try
677-
{
678-
topClickedVisual->SetUserData(
679-
"pause-update", static_cast<int>(1));
680-
}
681-
catch (std::bad_variant_access &)
682-
{
683-
// It's ok to get here
684-
}
655+
topClickedVisual->SetUserData(
656+
"pause-update", static_cast<int>(1));
685657
}
686658
else
687659
{
688660
this->transformControl.Detach();
689-
try
690-
{
691-
topClickedVisual->SetUserData(
692-
"pause-update", static_cast<int>(0));
693-
}
694-
catch (std::bad_variant_access &)
695-
{
696-
// It's ok to get here
697-
}
661+
topClickedVisual->SetUserData(
662+
"pause-update", static_cast<int>(0));
698663
}
699664
}
700665

@@ -708,14 +673,8 @@ void TransformControlPrivate::HandleMouseEvents()
708673
&& this->transformControl.Active())
709674
{
710675
if (this->transformControl.Node()){
711-
try
712-
{
713-
this->transformControl.Node()->SetUserData(
714-
"pause-update", static_cast<int>(1));
715-
} catch (std::bad_variant_access &)
716-
{
717-
// It's ok to get here
718-
}
676+
this->transformControl.Node()->SetUserData(
677+
"pause-update", static_cast<int>(1));
719678
}
720679

721680
this->blockOrbit = true;
@@ -744,14 +703,10 @@ void TransformControlPrivate::HandleMouseEvents()
744703
{
745704
auto visual = this->scene->VisualByIndex(i);
746705
auto entityId = kNullEntity;
747-
try
706+
if (std::holds_alternative<uint64_t>(visual->UserData("gazebo-entity")))
748707
{
749708
entityId = std::get<uint64_t>(visual->UserData("gazebo-entity"));
750709
}
751-
catch (std::bad_variant_access &)
752-
{
753-
// It's ok to get here
754-
}
755710
if (entityId == nodeId)
756711
{
757712
target = std::dynamic_pointer_cast<rendering::Node>(

0 commit comments

Comments
 (0)