diff --git a/examples/worlds/ackermann_steering.sdf b/examples/worlds/ackermann_steering.sdf
index b4fdc88d80..26c19d8565 100644
--- a/examples/worlds/ackermann_steering.sdf
+++ b/examples/worlds/ackermann_steering.sdf
@@ -221,7 +221,7 @@
- 0.554282 -0.625029 -0.025 -1.5707 0 0
+ 0.554283 -0.625029 -0.025 -1.5707 0 0
2
diff --git a/src/SystemLoader.cc b/src/SystemLoader.cc
index 23409c2188..5ab522edfd 100644
--- a/src/SystemLoader.cc
+++ b/src/SystemLoader.cc
@@ -75,14 +75,14 @@ class gz::sim::SystemLoaderPrivate
<< "]. Using [" << filename << "] instead." << std::endl;
}
- std::list paths = this->PluginPaths();
+ const std::list 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
@@ -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;
@@ -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;
@@ -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.
@@ -232,7 +232,7 @@ void SystemLoader::AddSystemPluginPath(const std::string &_path)
std::optional 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;
diff --git a/src/gui/plugins/apply_force_torque/ApplyForceTorque.cc b/src/gui/plugins/apply_force_torque/ApplyForceTorque.cc
index a2ca6ce79f..361891a194 100644
--- a/src/gui/plugins/apply_force_torque/ApplyForceTorque.cc
+++ b/src/gui/plugins/apply_force_torque/ApplyForceTorque.cc
@@ -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;
@@ -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());
diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc
index 5b5cd794e7..f9c6ec4b0a 100644
--- a/src/gui/plugins/component_inspector/ComponentInspector.cc
+++ b/src/gui/plugins/component_inspector/ComponentInspector.cc
@@ -967,7 +967,7 @@ bool ComponentInspector::eventFilter(QObject *_obj, QEvent *_event)
auto event = reinterpret_cast(_event);
if (event && !event->Data().empty())
{
- this->SetEntity(*event->Data().begin());
+ this->SetEntity(event->Data().front());
}
}
diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc
index 930ed465a1..0f8d1c99ab 100644
--- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc
+++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.cc
@@ -1014,7 +1014,7 @@ bool ComponentInspectorEditor::eventFilter(QObject *_obj, QEvent *_event)
auto event = reinterpret_cast(_event);
if (event && !event->Data().empty())
{
- this->SetEntity(*event->Data().begin());
+ this->SetEntity(event->Data().front());
}
}
diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.cc b/src/gui/plugins/joint_position_controller/JointPositionController.cc
index 428edb2291..bebef2d31c 100644
--- a/src/gui/plugins/joint_position_controller/JointPositionController.cc
+++ b/src/gui/plugins/joint_position_controller/JointPositionController.cc
@@ -315,7 +315,7 @@ bool JointPositionController::eventFilter(QObject *_obj, QEvent *_event)
auto event = reinterpret_cast(_event);
if (event && !event->Data().empty())
{
- this->SetModelEntity(*event->Data().begin());
+ this->SetModelEntity(event->Data().front());
}
}
diff --git a/src/gui/plugins/mouse_drag/MouseDrag.cc b/src/gui/plugins/mouse_drag/MouseDrag.cc
index 44b0cc3e35..3806820566 100644
--- a/src/gui/plugins/mouse_drag/MouseDrag.cc
+++ b/src/gui/plugins/mouse_drag/MouseDrag.cc
@@ -680,12 +680,13 @@ void MouseDragPrivate::HandleMouseEvents()
this->mode = MouseDragMode::NONE;
return;
}
- try
+ if (std::holds_alternative(
+ visual->Parent()->UserData("gazebo-entity")))
{
this->linkId =
std::get(visual->Parent()->UserData("gazebo-entity"));
}
- catch(std::bad_variant_access &e)
+ else
{
this->mode = MouseDragMode::NONE;
return;
diff --git a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc
index b5b25cc610..c7725fe974 100644
--- a/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc
+++ b/src/gui/plugins/playback_scrubber/PlaybackScrubber.cc
@@ -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();
diff --git a/src/gui/plugins/plot_3d/Plot3D.cc b/src/gui/plugins/plot_3d/Plot3D.cc
index 6e5e9e1314..377b87bd3a 100644
--- a/src/gui/plugins/plot_3d/Plot3D.cc
+++ b/src/gui/plugins/plot_3d/Plot3D.cc
@@ -270,7 +270,7 @@ bool Plot3D::eventFilter(QObject *_obj, QEvent *_event)
auto event = reinterpret_cast(_event);
if (event && !event->Data().empty())
{
- this->SetTargetEntity(*event->Data().begin());
+ this->SetTargetEntity(event->Data().front());
}
}
diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.cc b/src/gui/plugins/resource_spawner/ResourceSpawner.cc
index e206415218..92b50b4c47 100644
--- a/src/gui/plugins/resource_spawner/ResourceSpawner.cc
+++ b/src/gui/plugins/resource_spawner/ResourceSpawner.cc
@@ -81,7 +81,7 @@ namespace gz::sim
public: std::vector 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
@@ -441,7 +441,7 @@ bool compareByDownloaded(const Resource &a, const Resource &b)
/////////////////////////////////////////////////
void ResourceSpawner::FilterResources(std::vector &_resources)
{
- if (this->dataPtr->displayData.searchKeyword == "")
+ if (this->dataPtr->displayData.searchKeyword.empty())
return;
std::string searchKeyword = this->dataPtr->displayData.searchKeyword;
diff --git a/src/gui/plugins/select_entities/SelectEntities.cc b/src/gui/plugins/select_entities/SelectEntities.cc
index 13ddc7249b..2e6e872a21 100644
--- a/src/gui/plugins/select_entities/SelectEntities.cc
+++ b/src/gui/plugins/select_entities/SelectEntities.cc
@@ -171,15 +171,12 @@ void SelectEntitiesPrivate::HandleEntitySelection()
this->selectedEntitiesID.push_back(this->selectedEntitiesIDNew[i]);
Entity entityId = kNullEntity;
- try
+ if (std::holds_alternative(
+ visualToHighLight->UserData("gazebo-entity")))
{
entityId = std::get(
visualToHighLight->UserData("gazebo-entity"));
}
- catch(std::bad_variant_access &_e)
- {
- // It's ok to get here
- }
this->selectedEntities.push_back(entityId);
@@ -212,14 +209,10 @@ void SelectEntitiesPrivate::HandleEntitySelection()
}
Entity entityId = kNullEntity;
- try
+ if (std::holds_alternative(visual->UserData("gazebo-entity")))
{
entityId = std::get(visual->UserData("gazebo-entity"));
}
- catch(std::bad_variant_access &e)
- {
- // It's ok to get here
- }
this->selectionHelper.selectEntity = entityId;
@@ -243,14 +236,10 @@ void SelectEntitiesPrivate::LowlightNode(const rendering::VisualPtr &_visual)
Entity entityId = kNullEntity;
if (_visual)
{
- try
+ if (std::holds_alternative(_visual->UserData("gazebo-entity")))
{
entityId = std::get(_visual->UserData("gazebo-entity"));
}
- catch(std::bad_variant_access &)
- {
- // It's ok to get here
- }
}
if (this->wireBoxes.find(entityId) != this->wireBoxes.end())
{
@@ -271,14 +260,10 @@ void SelectEntitiesPrivate::HighlightNode(const rendering::VisualPtr &_visual)
}
Entity entityId = kNullEntity;
- try
+ if (std::holds_alternative(_visual->UserData("gazebo-entity")))
{
entityId = std::get(_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);
@@ -358,14 +343,11 @@ void SelectEntitiesPrivate::SetSelectedEntity(
if (topLevelVisual)
{
- try
+ if (std::holds_alternative(
+ topLevelVisual->UserData("gazebo-entity")))
{
entityId = std::get(topLevelVisual->UserData("gazebo-entity"));
}
- catch(std::bad_variant_access &)
- {
- // It's ok to get here
- }
}
if (entityId == kNullEntity)
@@ -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(
+ visual->UserData("gazebo-entity")))
{
entityId = std::get(visual->UserData("gazebo-entity"));
}
- catch(std::bad_variant_access &)
- {
- // It's ok to get here
- }
if (entityId == entity)
{
diff --git a/src/gui/plugins/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc
index 6912bc8942..5241e9ff31 100644
--- a/src/gui/plugins/transform_control/TransformControl.cc
+++ b/src/gui/plugins/transform_control/TransformControl.cc
@@ -712,7 +712,8 @@ void TransformControlPrivate::HandleMouseEvents()
{
this->transformControl.Node()->SetUserData(
"pause-update", static_cast(1));
- } catch (std::bad_variant_access &)
+ }
+ catch (std::bad_variant_access &)
{
// It's ok to get here
}
@@ -744,14 +745,10 @@ void TransformControlPrivate::HandleMouseEvents()
{
auto visual = this->scene->VisualByIndex(i);
auto entityId = kNullEntity;
- try
+ if (std::holds_alternative(visual->UserData("gazebo-entity")))
{
entityId = std::get(visual->UserData("gazebo-entity"));
}
- catch (std::bad_variant_access &)
- {
- // It's ok to get here
- }
if (entityId == nodeId)
{
target = std::dynamic_pointer_cast(
diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc
index 8e035dfb90..5c5015d9ef 100644
--- a/src/gui/plugins/view_angle/ViewAngle.cc
+++ b/src/gui/plugins/view_angle/ViewAngle.cc
@@ -336,11 +336,12 @@ bool ViewAngle::OnMoveToModelService(const gz::msgs::GUICamera &_msg,
return false;
}
Entity entityId = kNullEntity;
- try
+ if (std::holds_alternative(
+ visualToMove->UserData("gazebo-entity")))
{
entityId = std::get(visualToMove->UserData("gazebo-entity"));
}
- catch(std::bad_variant_access &_e)
+ else
{
gzerr << "Failed to get gazebo-entity user data ["
<< visualToMove->Name() << "]" << std::endl;
@@ -452,14 +453,10 @@ void ViewAnglePrivate::OnRender()
if (cam)
{
bool isUserCamera = false;
- try
+ if (std::holds_alternative(cam->UserData("user-camera")))
{
isUserCamera = std::get(cam->UserData("user-camera"));
}
- catch (std::bad_variant_access &)
- {
- continue;
- }
if (isUserCamera)
{
this->camera = cam;
@@ -496,14 +493,15 @@ void ViewAnglePrivate::OnRender()
if (!vis)
continue;
- try
+ if (std::holds_alternative(
+ vis->UserData("gazebo-entity")))
{
if (std::get(vis->UserData("gazebo-entity")) != entity)
{
continue;
}
}
- catch (std::bad_variant_access &)
+ else
{
continue;
}
diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc
index 92ceedbfbb..e09ef27ce5 100644
--- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc
+++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc
@@ -562,8 +562,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
// create new wireframe visuals
for (const auto &link : this->newWireframeVisualLinks)
{
- std::vector visEntities =
- this->linkToVisualEntities[link];
+ const auto &visEntities = this->linkToVisualEntities[link];
for (const auto &visEntity : visEntities)
{
@@ -592,8 +591,7 @@ void VisualizationCapabilitiesPrivate::OnRender()
// create new transparent visuals
for (const auto &link : this->newTransparentVisualLinks)
{
- std::vector visEntities =
- this->linkToVisualEntities[link];
+ const auto &visEntities = this->linkToVisualEntities[link];
for (const auto &visEntity : visEntities)
{
@@ -1737,7 +1735,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::VisualByEntity(
{
auto visual = this->scene->VisualByIndex(i);
- try
+ if (std::holds_alternative(visual->UserData("gazebo-entity")))
{
Entity visualEntity = std::get(
visual->UserData("gazebo-entity"));
@@ -1747,10 +1745,6 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::VisualByEntity(
return visual;
}
}
- catch (std::bad_variant_access &)
- {
- // It's ok to get here
- }
}
return nullptr;
}
diff --git a/src/systems/apply_joint_force/ApplyJointForce.cc b/src/systems/apply_joint_force/ApplyJointForce.cc
index d1bc8cf0b9..173913e9fe 100644
--- a/src/systems/apply_joint_force/ApplyJointForce.cc
+++ b/src/systems/apply_joint_force/ApplyJointForce.cc
@@ -96,7 +96,7 @@ void ApplyJointForce::Configure(const Entity &_entity,
this->dataPtr->jointName = sdfElem->Get();
}
- if (this->dataPtr->jointName == "")
+ if (this->dataPtr->jointName.empty())
{
gzerr << "ApplyJointForce found an empty jointName parameter. "
<< "Failed to initialize.";
diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.cc b/src/systems/collada_world_exporter/ColladaWorldExporter.cc
index 3724ab95f1..30d22ec48e 100644
--- a/src/systems/collada_world_exporter/ColladaWorldExporter.cc
+++ b/src/systems/collada_world_exporter/ColladaWorldExporter.cc
@@ -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++)
{
diff --git a/src/systems/environmental_sensor_system/EnvironmentalSensorSystem.cc b/src/systems/environmental_sensor_system/EnvironmentalSensorSystem.cc
index f1fd42ae56..ec548dc646 100644
--- a/src/systems/environmental_sensor_system/EnvironmentalSensorSystem.cc
+++ b/src/systems/environmental_sensor_system/EnvironmentalSensorSystem.cc
@@ -47,12 +47,12 @@
using namespace gz;
using namespace gz::sim;
-/// Sensor prefix to be used. All envionment_sensors are to be prefixed by
+/// Sensor prefix to be used. All enviornment_sensors are to be prefixed by
/// "environment_sensor/" in their gz:type field.
constexpr char SENSOR_TYPE_PREFIX[] = "environmental_sensor/";
////////////////////////////////////////////////////////////////
-/// \brief Envirtonment Sensor used for looking up environment values in our
+/// \brief Environment Sensor used for looking up environment values in our
/// CSV file.
class EnvironmentalSensor : public gz::sensors::Sensor
{
@@ -199,7 +199,7 @@ class EnvironmentalSensor : public gz::sensors::Sensor
std::optional dataPoints[3];
for (std::size_t i = 0; i < this->numberOfFields; ++i)
{
- if (this->fieldName[i] == "")
+ if (this->fieldName[i].empty())
{
// Empty field name means the column should default to zero.
dataPoints[i] = 0;
@@ -225,7 +225,7 @@ class EnvironmentalSensor : public gz::sensors::Sensor
*msg.mutable_header()->mutable_stamp() = gz::msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
- frame->add_value((this->frameId == "") ? this->Name() : this->frameId);
+ frame->add_value((this->frameId.empty()) ? this->Name() : this->frameId);
auto data = dataPoints[0];
if (!data.has_value())
{
@@ -242,7 +242,7 @@ class EnvironmentalSensor : public gz::sensors::Sensor
*msg.mutable_header()->mutable_stamp() = gz::msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
- frame->add_value((this->frameId == "") ? this->Name() : this->frameId);
+ frame->add_value((this->frameId.empty()) ? this->Name() : this->frameId);
if (!dataPoints[0].has_value() || !dataPoints[1].has_value()
|| !dataPoints[2].has_value())
@@ -291,7 +291,7 @@ class EnvironmentalSensor : public gz::sensors::Sensor
this->gridField = data;
for (std::size_t i = 0; i < this->numberOfFields; ++i)
{
- if (this->fieldName[i] == "")
+ if (this->fieldName[i].empty())
continue;
this->session[i] =
diff --git a/test/integration/battery_plugin.cc b/test/integration/battery_plugin.cc
index 7f31376af4..980d481fb0 100644
--- a/test/integration/battery_plugin.cc
+++ b/test/integration/battery_plugin.cc
@@ -393,7 +393,7 @@ TEST_F(BatteryPluginTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(PowerDrainTopic))
components::BatterySoC::typeId));
auto batComp = ecm->Component(batEntity);
- // Check state of charge should be 1, since the batery has not drained
+ // Check state of charge should be 1, since the battery has not drained
// and the is equivalent to the .
EXPECT_DOUBLE_EQ(batComp->Data(), 1.0);
@@ -407,7 +407,7 @@ TEST_F(BatteryPluginTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(PowerDrainTopic))
// Run the server again.
server.Run(true, 100, false);
- // The state of charge should be <1, since the batery has started
+ // The state of charge should be <1, since the battery has started
// draining.
double stateOfCharge = batComp->Data();
EXPECT_LT(batComp->Data(), 1.0);
diff --git a/test/integration/contact_system.cc b/test/integration/contact_system.cc
index 2ac7694388..b5a7644f24 100644
--- a/test/integration/contact_system.cc
+++ b/test/integration/contact_system.cc
@@ -170,7 +170,7 @@ TEST_F(ContactSystemTest,
{
ASSERT_EQ(1, contact.position_size());
bool entityNameEmpty =
- contact.collision1().name() == "";
+ contact.collision1().name().empty();
EXPECT_TRUE(entityNameEmpty);
}
}
diff --git a/test/integration/sensors_system_battery.cc b/test/integration/sensors_system_battery.cc
index 49bfd0cd0b..205d5f1119 100644
--- a/test/integration/sensors_system_battery.cc
+++ b/test/integration/sensors_system_battery.cc
@@ -121,7 +121,7 @@ TEST_F(SensorsFixture, SensorsBatteryState)
components::BatterySoC::typeId));
auto batComp = ecm->Component(batEntity);
- // Check state of charge should be 1, since the batery has not drained
+ // Check state of charge should be 1, since the battery has not drained
// and the is equivalent ot the .
EXPECT_DOUBLE_EQ(batComp->Data(), 1.0);
@@ -140,7 +140,7 @@ TEST_F(SensorsFixture, SensorsBatteryState)
// Run the server again.
server.Run(true, 50, false);
- // The state of charge should be <1, since the batery has started
+ // The state of charge should be <1, since the battery has started
// draining.
EXPECT_LT(batComp->Data(), 1.0);