From 381a3073012ace8795054ae23f36e56cd9140c6a Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 28 Sep 2023 16:31:58 +0000 Subject: [PATCH 1/4] Tidy up SDFEntityCreator Signed-off-by: Michael Carroll --- include/gz/sim/SdfEntityCreator.hh | 23 +------------- src/SdfEntityCreator.cc | 49 +++++++++--------------------- 2 files changed, 16 insertions(+), 56 deletions(-) diff --git a/include/gz/sim/SdfEntityCreator.hh b/include/gz/sim/SdfEntityCreator.hh index 8e5292ef10..2808b21e9a 100644 --- a/include/gz/sim/SdfEntityCreator.hh +++ b/include/gz/sim/SdfEntityCreator.hh @@ -66,27 +66,6 @@ namespace gz public: explicit SdfEntityCreator(EntityComponentManager &_ecm, EventManager &_eventManager); - /// \brief Copy constructor - /// \param[in] _creator SdfEntityCreator to copy. - public: SdfEntityCreator(const SdfEntityCreator &_creator); - - /// \brief Move constructor - /// \param[in] _creator SdfEntityCreator to move. - public: SdfEntityCreator(SdfEntityCreator &&_creator) noexcept; - - /// \brief Move assignment operator. - /// \param[in] _creator SdfEntityCreator component to move. - /// \return Reference to this. - public: SdfEntityCreator &operator=(SdfEntityCreator &&_creator) noexcept; - - /// \brief Copy assignment operator. - /// \param[in] _creator SdfEntityCreator to copy. - /// \return Reference to this. - public: SdfEntityCreator &operator=(const SdfEntityCreator &_creator); - - /// \brief Destructor. - public: ~SdfEntityCreator(); - /// \brief Create all entities that exist in the sdf::World object and /// load their plugins. /// \param[in] _world SDF world object. @@ -187,7 +166,7 @@ namespace gz bool _staticParent); /// \brief Pointer to private data. - private: std::unique_ptr dataPtr; + GZ_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index 638797ba6f..a097d1a4d8 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -84,7 +84,11 @@ #include "gz/sim/components/WindMode.hh" #include "gz/sim/components/World.hh" -class gz::sim::SdfEntityCreatorPrivate + +namespace gz::sim +{ + +class SdfEntityCreator::Implementation { /// \brief Pointer to entity component manager. We don't assume ownership. public: EntityComponentManager *ecm{nullptr}; @@ -105,13 +109,11 @@ class gz::sim::SdfEntityCreatorPrivate public: std::map newVisuals; }; -using namespace gz; -using namespace sim; - +namespace { ///////////////////////////////////////////////// /// \brief Resolve the pose of an SDF DOM object with respect to its relative_to /// frame. If that fails, return the raw pose -static math::Pose3d ResolveSdfPose(const sdf::SemanticPose &_semPose) +math::Pose3d ResolveSdfPose(const sdf::SemanticPose &_semPose) { math::Pose3d pose; ::sdf::Errors errors = _semPose.Resolve(pose); @@ -124,7 +126,7 @@ static math::Pose3d ResolveSdfPose(const sdf::SemanticPose &_semPose) } ///////////////////////////////////////////////// -static std::optional ResolveJointAxis( +std::optional ResolveJointAxis( const sdf::JointAxis &_unresolvedAxis) { math::Vector3d axisXyz; @@ -156,9 +158,9 @@ static std::optional ResolveJointAxis( /// \param[in] _ecm Entity component manager /// \return The Entity of the descendent link or kNullEntity if link was not /// found -static Entity FindDescendentLinkEntityByName(const std::string &_name, - const Entity &_model, - const EntityComponentManager &_ecm) +Entity FindDescendentLinkEntityByName(const std::string &_name, + const Entity &_model, + const EntityComponentManager &_ecm) { auto ind = _name.find(sdf::kScopeDelimiter); std::vector candidates; @@ -185,40 +187,17 @@ static Entity FindDescendentLinkEntityByName(const std::string &_name, return candidates.front(); } } +} // namespace ////////////////////////////////////////////////// SdfEntityCreator::SdfEntityCreator(EntityComponentManager &_ecm, EventManager &_eventManager) - : dataPtr(std::make_unique()) + : dataPtr(gz::utils::MakeImpl()) { this->dataPtr->ecm = &_ecm; this->dataPtr->eventManager = &_eventManager; } -///////////////////////////////////////////////// -SdfEntityCreator::SdfEntityCreator(const SdfEntityCreator &_creator) - : dataPtr(std::make_unique(*_creator.dataPtr)) -{ -} - -///////////////////////////////////////////////// -SdfEntityCreator::SdfEntityCreator(SdfEntityCreator &&_creator) noexcept - = default; - -////////////////////////////////////////////////// -SdfEntityCreator::~SdfEntityCreator() = default; - -///////////////////////////////////////////////// -SdfEntityCreator &SdfEntityCreator::operator=(const SdfEntityCreator &_creator) -{ - *this->dataPtr = (*_creator.dataPtr); - return *this; -} - -///////////////////////////////////////////////// -SdfEntityCreator &SdfEntityCreator::operator=(SdfEntityCreator &&_creator) - noexcept = default; - ////////////////////////////////////////////////// Entity SdfEntityCreator::CreateEntities(const sdf::World *_world) { @@ -1085,3 +1064,5 @@ void SdfEntityCreator::SetParent(Entity _child, Entity _parent) this->dataPtr->ecm->CreateComponent(_child, components::ParentEntity(_parent)); } + +} // namespace gz::sim From 8e91dc9cd747a2a8dcdc1efd1129e0e6c93fbd29 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 28 Sep 2023 17:11:47 +0000 Subject: [PATCH 2/4] Remove duplicated functionality from LevelManager Signed-off-by: Michael Carroll --- src/LevelManager.cc | 89 ++--------------------------------------- src/SdfEntityCreator.cc | 15 ++++++- 2 files changed, 18 insertions(+), 86 deletions(-) diff --git a/src/LevelManager.cc b/src/LevelManager.cc index 0513fb4f30..df972ddbd2 100644 --- a/src/LevelManager.cc +++ b/src/LevelManager.cc @@ -97,53 +97,11 @@ LevelManager::LevelManager(SimulationRunner *_runner, const bool _useLevels) ///////////////////////////////////////////////// void LevelManager::ReadLevelPerformerInfo() { - // \todo(anyone) Use SdfEntityCreator to avoid duplication - this->worldEntity = this->runner->entityCompMgr.CreateEntity(); + this->worldEntity = + this->entityCreator->CreateEntities(this->runner->sdfWorld); - // World components - this->runner->entityCompMgr.CreateComponent(this->worldEntity, - components::World()); - this->runner->entityCompMgr.CreateComponent( - this->worldEntity, components::Name(this->runner->sdfWorld->Name())); - - this->runner->entityCompMgr.CreateComponent(this->worldEntity, - components::Gravity(this->runner->sdfWorld->Gravity())); - - auto physics = this->runner->sdfWorld->PhysicsByIndex(0); - if (!physics) - { - physics = this->runner->sdfWorld->PhysicsDefault(); - } - this->runner->entityCompMgr.CreateComponent(this->worldEntity, - components::Physics(*physics)); - - // Populate physics options that aren't accessible outside the Element() - // See https://github.com/osrf/sdformat/issues/508 - if (physics->Element() && physics->Element()->HasElement("dart")) - { - auto dartElem = physics->Element()->GetElement("dart"); - - if (dartElem->HasElement("collision_detector")) - { - auto collisionDetector = - dartElem->Get("collision_detector"); - - this->runner->entityCompMgr.CreateComponent(worldEntity, - components::PhysicsCollisionDetector(collisionDetector)); - } - if (dartElem->HasElement("solver") && - dartElem->GetElement("solver")->HasElement("solver_type")) - { - auto solver = - dartElem->GetElement("solver")->Get("solver_type"); - - this->runner->entityCompMgr.CreateComponent(worldEntity, - components::PhysicsSolver(solver)); - } - } - - this->runner->entityCompMgr.CreateComponent(this->worldEntity, - components::MagneticField(this->runner->sdfWorld->MagneticField())); + // These elements are populated here rather than in the SdfEntityCreator, + // because the serverConfig is available in this context this->runner->entityCompMgr.CreateComponent(this->worldEntity, components::PhysicsEnginePlugin( @@ -167,41 +125,6 @@ void LevelManager::ReadLevelPerformerInfo() auto worldElem = this->runner->sdfWorld->Element(); - // Create Wind - auto windEntity = this->runner->entityCompMgr.CreateEntity(); - this->runner->entityCompMgr.CreateComponent(windEntity, components::Wind()); - this->runner->entityCompMgr.CreateComponent( - windEntity, components::WorldLinearVelocity( - this->runner->sdfWorld->WindLinearVelocity())); - // Initially the wind linear velocity is used as the seed velocity - this->runner->entityCompMgr.CreateComponent( - windEntity, components::WorldLinearVelocitySeed( - this->runner->sdfWorld->WindLinearVelocity())); - - this->entityCreator->SetParent(windEntity, this->worldEntity); - - // scene - if (this->runner->sdfWorld->Scene()) - { - this->runner->entityCompMgr.CreateComponent(this->worldEntity, - components::Scene(*this->runner->sdfWorld->Scene())); - } - - // atmosphere - if (this->runner->sdfWorld->Atmosphere()) - { - this->runner->entityCompMgr.CreateComponent(this->worldEntity, - components::Atmosphere(*this->runner->sdfWorld->Atmosphere())); - } - - // spherical coordinates - if (this->runner->sdfWorld->SphericalCoordinates()) - { - this->runner->entityCompMgr.CreateComponent(this->worldEntity, - components::SphericalCoordinates( - *this->runner->sdfWorld->SphericalCoordinates())); - } - // TODO(anyone) This should probably go somewhere else as it is a global // constant. const std::string kPluginName{"gz::sim"}; @@ -238,10 +161,6 @@ void LevelManager::ReadLevelPerformerInfo() // Load world plugins. this->runner->EventMgr().Emit(this->worldEntity, this->runner->sdfWorld->Plugins()); - - // Store the world's SDF DOM to be used when saving the world to file - this->runner->entityCompMgr.CreateComponent( - worldEntity, components::WorldSdf(*this->runner->sdfWorld)); } ///////////////////////////////////////////////// diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index a097d1a4d8..fba710d35a 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -47,11 +47,11 @@ #include "gz/sim/components/JointAxis.hh" #include "gz/sim/components/JointType.hh" #include "gz/sim/components/LaserRetro.hh" -#include "gz/sim/components/Lidar.hh" #include "gz/sim/components/Light.hh" #include "gz/sim/components/LightType.hh" #include "gz/sim/components/LinearAcceleration.hh" #include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/components/LinearVelocitySeed.hh" #include "gz/sim/components/Link.hh" #include "gz/sim/components/LogicalCamera.hh" #include "gz/sim/components/MagneticField.hh" @@ -81,6 +81,7 @@ #include "gz/sim/components/Visibility.hh" #include "gz/sim/components/Visual.hh" #include "gz/sim/components/WideAngleCamera.hh" +#include "gz/sim/components/Wind.hh" #include "gz/sim/components/WindMode.hh" #include "gz/sim/components/World.hh" @@ -305,6 +306,18 @@ Entity SdfEntityCreator::CreateEntities(const sdf::World *_world) this->dataPtr->ecm->CreateComponent(worldEntity, components::MagneticField(_world->MagneticField())); + // Wind + auto windEntity = this->dataPtr->ecm->CreateEntity(); + this->dataPtr->ecm->CreateComponent(windEntity, components::Wind()); + this->dataPtr->ecm->CreateComponent( + windEntity, components::WorldLinearVelocity( + _world->WindLinearVelocity())); + // Initially the wind linear velocity is used as the seed velocity + this->dataPtr->ecm->CreateComponent( + windEntity, components::WorldLinearVelocitySeed( + _world->WindLinearVelocity())); + this->SetParent(windEntity, worldEntity); + this->dataPtr->eventManager->Emit(worldEntity, _world->Plugins()); From 4e3437a483891acfb0b61eb7fb664259e9d67095 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 4 Oct 2023 10:09:57 -0500 Subject: [PATCH 3/4] Cleanups related to stricter warnings in C++ (#2180) Signed-off-by: Michael Carroll --- include/gz/sim/System.hh | 20 +++++++++++++++++++ .../gz/sim/detail/EntityComponentManager.hh | 16 +++------------ .../CiVctCascadePrivate.cc | 2 +- .../GlobalIlluminationCiVct.cc | 2 +- src/network/NetworkManager.cc | 1 + .../afsm/include/afsm/detail/transitions.hpp | 8 ++++---- .../JointTrajectoryController.cc | 8 ++++---- src/systems/physics/EntityFeatureMap_TEST.cc | 3 ++- src/systems/physics/Physics.cc | 3 ++- src/systems/thruster/Thruster.cc | 7 ++----- test/integration/ModelPhotoShootTest.hh | 3 ++- test/integration/thruster.cc | 1 - test/integration/tracked_vehicle_system.cc | 3 ++- 13 files changed, 44 insertions(+), 33 deletions(-) diff --git a/include/gz/sim/System.hh b/include/gz/sim/System.hh index cc0139161e..51be1708b1 100644 --- a/include/gz/sim/System.hh +++ b/include/gz/sim/System.hh @@ -88,6 +88,10 @@ namespace gz /// and components are loaded from the corresponding SDF world, and before /// simulation begins exectution. class ISystemConfigure { + + /// \brief Destructor + public: virtual ~ISystemConfigure() = default; + /// \brief Configure the system /// \param[in] _entity The entity this plugin is attached to. /// \param[in] _sdf The SDF Element associated with this system plugin. @@ -108,6 +112,10 @@ namespace gz /// ISystemConfigureParameters::ConfigureParameters is called after /// ISystemConfigure::Configure. class ISystemConfigureParameters { + + /// \brief Destructor + public: virtual ~ISystemConfigureParameters() = default; + /// \brief Configure the parameters of the system. /// \param[in] _registry The parameter registry. public: virtual void ConfigureParameters( @@ -117,6 +125,9 @@ namespace gz class ISystemReset { + /// \brief Destructor + public: virtual ~ISystemReset () = default; + public: virtual void Reset(const UpdateInfo &_info, EntityComponentManager &_ecm) = 0; }; @@ -124,6 +135,9 @@ namespace gz /// \class ISystemPreUpdate ISystem.hh gz/sim/System.hh /// \brief Interface for a system that uses the PreUpdate phase class ISystemPreUpdate { + /// \brief Destructor + public: virtual ~ISystemPreUpdate() = default; + public: virtual void PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) = 0; }; @@ -131,6 +145,9 @@ namespace gz /// \class ISystemUpdate ISystem.hh gz/sim/System.hh /// \brief Interface for a system that uses the Update phase class ISystemUpdate { + /// \brief Destructor + public: virtual ~ISystemUpdate() = default; + public: virtual void Update(const UpdateInfo &_info, EntityComponentManager &_ecm) = 0; }; @@ -138,6 +155,9 @@ namespace gz /// \class ISystemPostUpdate ISystem.hh gz/sim/System.hh /// \brief Interface for a system that uses the PostUpdate phase class ISystemPostUpdate{ + /// \brief Destructor + public: virtual ~ISystemPostUpdate() = default; + public: virtual void PostUpdate(const UpdateInfo &_info, const EntityComponentManager &_ecm) = 0; }; diff --git a/include/gz/sim/detail/EntityComponentManager.hh b/include/gz/sim/detail/EntityComponentManager.hh index 7ce3096e4a..f21c8c8cfe 100644 --- a/include/gz/sim/detail/EntityComponentManager.hh +++ b/include/gz/sim/detail/EntityComponentManager.hh @@ -42,9 +42,7 @@ inline namespace GZ_SIM_VERSION_NAMESPACE { namespace traits { /// \brief Helper struct to determine if an equality operator is present. - struct TestEqualityOperator - { - }; + struct TestEqualityOperator {}; template TestEqualityOperator operator == (const T&, const T&); @@ -52,20 +50,12 @@ namespace traits template struct HasEqualityOperator { -#if !defined(_MSC_VER) -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wnonnull" -#endif enum { - // False positive codecheck "Using C-style cast" - value = !std::is_same::value // NOLINT + value = !std::is_same() == std::declval()), TestEqualityOperator>::value }; -#if !defined(_MSC_VER) -#pragma GCC diagnostic pop -#endif }; -} +} // namespace traits ////////////////////////////////////////////////// /// \brief Helper function to compare two objects of the same type using its diff --git a/src/gui/plugins/global_illumination_civct/CiVctCascadePrivate.cc b/src/gui/plugins/global_illumination_civct/CiVctCascadePrivate.cc index de9149b5b1..71524fb471 100644 --- a/src/gui/plugins/global_illumination_civct/CiVctCascadePrivate.cc +++ b/src/gui/plugins/global_illumination_civct/CiVctCascadePrivate.cc @@ -70,7 +70,7 @@ void CiVctCascadePrivate::UpdateAreaHalfSize(int _axis, float _halfSize) std::lock_guard lock(this->serviceMutex); math::Vector3d areaHalfSize = this->cascade->AreaHalfSize(); - areaHalfSize[(size_t)_axis] = static_cast(_halfSize); + areaHalfSize[static_cast(_axis)] = static_cast(_halfSize); this->cascade->SetAreaHalfSize(areaHalfSize); } diff --git a/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.cc b/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.cc index d2b8f4c20c..38ac3dad12 100644 --- a/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.cc +++ b/src/gui/plugins/global_illumination_civct/GlobalIlluminationCiVct.cc @@ -796,7 +796,7 @@ void GlobalIlluminationCiVct::PopCascade() QObject *GlobalIlluminationCiVct::GetCascade(int _idx) const { std::lock_guard lock(this->dataPtr->serviceMutex); - return this->dataPtr->cascades[(size_t)_idx].get(); + return this->dataPtr->cascades[static_cast(_idx)].get(); } ////////////////////////////////////////////////// diff --git a/src/network/NetworkManager.cc b/src/network/NetworkManager.cc index 070264a2f3..e1cde9935e 100644 --- a/src/network/NetworkManager.cc +++ b/src/network/NetworkManager.cc @@ -81,6 +81,7 @@ std::unique_ptr NetworkManager::Create( case NetworkRole::ReadOnly: // \todo(mjcarroll): Enable ReadOnly gzwarn << "ReadOnly role not currently supported" << std::endl; + break; case NetworkRole::None: break; default: diff --git a/src/systems/elevator/vender/afsm/include/afsm/detail/transitions.hpp b/src/systems/elevator/vender/afsm/include/afsm/detail/transitions.hpp index e4fe1fa821..1619b4b721 100644 --- a/src/systems/elevator/vender/afsm/include/afsm/detail/transitions.hpp +++ b/src/systems/elevator/vender/afsm/include/afsm/detail/transitions.hpp @@ -444,19 +444,19 @@ class state_transition_table { state_transition_table(fsm_type& fsm, state_transition_table const& rhs) : fsm_{&fsm}, - current_state_{ (::std::size_t)rhs.current_state_ }, + current_state_{ static_cast<::std::size_t>(rhs.current_state_) }, states_{ inner_states_constructor::copy_construct(fsm, rhs.states_) } {} state_transition_table(fsm_type& fsm, state_transition_table&& rhs) : fsm_{&fsm}, - current_state_{ (::std::size_t)rhs.current_state_ }, + current_state_{ static_cast<::std::size_t>(rhs.current_state_) }, states_{ inner_states_constructor::move_construct(fsm, ::std::move(rhs.states_)) } {} state_transition_table(state_transition_table const&) = delete; state_transition_table(state_transition_table&& rhs) : fsm_{rhs.fsm_}, - current_state_{ (::std::size_t)rhs.current_state_ }, + current_state_{ static_cast<::std::size_t>(rhs.current_state_) }, states_{ ::std::move(rhs.states_) } {} state_transition_table& @@ -499,7 +499,7 @@ class state_transition_table { ::std::size_t current_state() const - { return (::std::size_t)current_state_; } + { return static_cast<::std::size_t>(current_state_); } void set_current_state(::std::size_t val) diff --git a/src/systems/joint_traj_control/JointTrajectoryController.cc b/src/systems/joint_traj_control/JointTrajectoryController.cc index d6882f9796..49e9295489 100644 --- a/src/systems/joint_traj_control/JointTrajectoryController.cc +++ b/src/systems/joint_traj_control/JointTrajectoryController.cc @@ -922,19 +922,19 @@ void ActuatedJoint::SetTarget( const gz::msgs::JointTrajectoryPoint &_targetPoint, const size_t &_jointIndex) { - if ((signed)_jointIndex < _targetPoint.positions_size()) + if (static_cast(_jointIndex) < _targetPoint.positions_size()) { this->target.position = _targetPoint.positions(_jointIndex); } - if ((signed)_jointIndex < _targetPoint.velocities_size()) + if (static_cast(_jointIndex) < _targetPoint.velocities_size()) { this->target.velocity = _targetPoint.velocities(_jointIndex); } - if ((signed)_jointIndex < _targetPoint.accelerations_size()) + if (static_cast(_jointIndex) < _targetPoint.accelerations_size()) { this->target.acceleration = _targetPoint.accelerations(_jointIndex); } - if ((signed)_jointIndex < _targetPoint.effort_size()) + if (static_cast(_jointIndex) < _targetPoint.effort_size()) { this->target.effort = _targetPoint.effort(_jointIndex); } diff --git a/src/systems/physics/EntityFeatureMap_TEST.cc b/src/systems/physics/EntityFeatureMap_TEST.cc index 948d83851a..0a8eb2ad06 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -25,6 +25,7 @@ #include #include #include +#include #include #include #include @@ -57,7 +58,7 @@ class EntityFeatureMapFixture: public InternalFixture<::testing::Test> const std::string pluginLib = "gz-physics-dartsim-plugin"; common::SystemPaths systemPaths; - systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths({gz::physics::getEngineInstallDir()}); auto pathToLib = systemPaths.FindSharedLibrary(pluginLib); ASSERT_FALSE(pathToLib.empty()) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 047e209db9..823e38b764 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -61,6 +61,7 @@ #include #include #include +#include #include #include #include @@ -806,7 +807,7 @@ void Physics::Configure(const Entity &_entity, // * Engines installed with gz-physics common::SystemPaths systemPaths; systemPaths.SetPluginPathEnv(this->dataPtr->pluginPathEnv); - systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths({gz::physics::getEngineInstallDir()}); auto pathToLib = systemPaths.FindSharedLibrary(pluginLib); diff --git a/src/systems/thruster/Thruster.cc b/src/systems/thruster/Thruster.cc index e7663924b2..6b69a2508d 100644 --- a/src/systems/thruster/Thruster.cc +++ b/src/systems/thruster/Thruster.cc @@ -694,9 +694,6 @@ void Thruster::PreUpdate( gz::sim::Link link(this->dataPtr->linkEntity); - - auto pose = worldPose(this->dataPtr->linkEntity, _ecm); - // TODO(arjo129): add logic for custom coordinate frame // Convert joint axis to the world frame const auto linkWorldPose = worldPose(this->dataPtr->linkEntity, _ecm); @@ -704,8 +701,8 @@ void Thruster::PreUpdate( auto unitVector = jointWorldPose.Rot().RotateVector(this->dataPtr->jointAxis).Normalize(); - double desiredThrust; - double desiredPropellerAngVel; + double desiredThrust {0.0}; + double desiredPropellerAngVel {0.0}; { std::lock_guard lock(this->dataPtr->mtx); desiredThrust = this->dataPtr->thrust; diff --git a/test/integration/ModelPhotoShootTest.hh b/test/integration/ModelPhotoShootTest.hh index 5636036267..9cb0961004 100644 --- a/test/integration/ModelPhotoShootTest.hh +++ b/test/integration/ModelPhotoShootTest.hh @@ -108,7 +108,8 @@ void testImages(const std::string &_imageFile, } } } - ASSERT_GT((float)equalPixels/(float)totalPixels, 0.99); + ASSERT_GT( + static_cast(equalPixels)/static_cast(totalPixels), 0.99); // Deleting files so they do not affect future tests EXPECT_EQ(remove(imageFilePath.c_str()), 0); diff --git a/test/integration/thruster.cc b/test/integration/thruster.cc index 3a365ea69f..f07f2c2f3c 100644 --- a/test/integration/thruster.cc +++ b/test/integration/thruster.cc @@ -337,7 +337,6 @@ void ThrusterTest::TestWorld(const std::string &_world, propellerLinVels.clear(); // Make sure that when the deadband is disabled // commands below the deadband should create a movement - auto latest_pose = modelPoses.back(); msgs::Boolean db_msg; if (_namespace == "deadband") { diff --git a/test/integration/tracked_vehicle_system.cc b/test/integration/tracked_vehicle_system.cc index 69b7155f07..9ee6c2f6e1 100644 --- a/test/integration/tracked_vehicle_system.cc +++ b/test/integration/tracked_vehicle_system.cc @@ -33,6 +33,7 @@ #include #include #include +#include #include #include #include @@ -111,7 +112,7 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> // modifications) common::SystemPaths systemPaths; systemPaths.SetPluginPathEnv("GZ_SIM_PHYSICS_ENGINE_PATH"); - systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths({gz::physics::getEngineInstallDir()}); auto pathToLib = systemPaths.FindSharedLibrary(*pluginLib); ASSERT_FALSE(pathToLib.empty()) From ec52c335657a3e036a5c1e62d0977cd1fdcef99e Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Fri, 13 Oct 2023 14:18:37 +0000 Subject: [PATCH 4/4] Lint Signed-off-by: Michael Carroll --- include/gz/sim/detail/EntityComponentManager.hh | 3 ++- src/systems/physics/Physics.cc | 1 - 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/include/gz/sim/detail/EntityComponentManager.hh b/include/gz/sim/detail/EntityComponentManager.hh index f21c8c8cfe..2438f5b333 100644 --- a/include/gz/sim/detail/EntityComponentManager.hh +++ b/include/gz/sim/detail/EntityComponentManager.hh @@ -52,7 +52,8 @@ namespace traits { enum { - value = !std::is_same() == std::declval()), TestEqualityOperator>::value + value = !std::is_same() == std::declval()), TestEqualityOperator>::value }; }; } // namespace traits diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index aa109a10e8..5b6d6f3a80 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -48,7 +48,6 @@ #include #include #include -#include #include #include