Skip to content
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
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>
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

in other 3 places in file it's 0.554283, but here it's 0.554282, aligned to simplify find-replace for users

<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
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());
}
}

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());
}
}

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());
}
}

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")))
{
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")))
{
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")))
{
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")))
{
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")))
{
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")))
{
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
71 changes: 13 additions & 58 deletions src/gui/plugins/transform_control/TransformControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -471,15 +471,8 @@ void TransformControlPrivate::HandleTransform()
{
if (this->transformControl.Node())
{
try
{
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(0));
}
catch (std::bad_variant_access &)
{
// It's ok to get here
}
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(0));
}

if (this->transformControl.Active())
Expand Down Expand Up @@ -550,15 +543,8 @@ void TransformControlPrivate::HandleMouseEvents()
this->transformControl.Start();
if (this->transformControl.Node())
{
try
{
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(1));
}
catch (std::bad_variant_access &)
{
// It's ok to get here
}
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(1));
}
}
else
Expand All @@ -584,15 +570,8 @@ void TransformControlPrivate::HandleMouseEvents()
{
if (this->transformControl.Node())
{
try
{
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(0));
}
catch (std::bad_variant_access &)
{
// It's ok to get here
}
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(0));
}
if (!_result)
gzerr << "Error setting pose" << std::endl;
Expand Down Expand Up @@ -673,28 +652,14 @@ void TransformControlPrivate::HandleMouseEvents()
if (topClickedNode == topClickedVisual)
{
this->transformControl.Attach(topClickedVisual);
try
{
topClickedVisual->SetUserData(
"pause-update", static_cast<int>(1));
}
catch (std::bad_variant_access &)
{
// It's ok to get here
}
topClickedVisual->SetUserData(
"pause-update", static_cast<int>(1));
}
else
{
this->transformControl.Detach();
try
{
topClickedVisual->SetUserData(
"pause-update", static_cast<int>(0));
}
catch (std::bad_variant_access &)
{
// It's ok to get here
}
topClickedVisual->SetUserData(
"pause-update", static_cast<int>(0));
}
}

Expand All @@ -708,14 +673,8 @@ void TransformControlPrivate::HandleMouseEvents()
&& this->transformControl.Active())
{
if (this->transformControl.Node()){
try
{
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(1));
} catch (std::bad_variant_access &)
{
// It's ok to get here
}
this->transformControl.Node()->SetUserData(
"pause-update", static_cast<int>(1));
}

this->blockOrbit = true;
Expand Down Expand Up @@ -744,14 +703,10 @@ void TransformControlPrivate::HandleMouseEvents()
{
auto visual = this->scene->VisualByIndex(i);
auto entityId = kNullEntity;
try
if (std::holds_alternative<uint64_t>(visual->UserData("gazebo-entity")))
{
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
Loading
Loading