From b140329abacec3cf1961b1dc7924d4985fed556f Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Sat, 13 Jan 2024 01:18:41 +0000 Subject: [PATCH] CollisionPairMaxTotalContacts -> CollisionPairMaxContacts Signed-off-by: Ian Chen --- dartsim/src/GzOdeCollisionDetector.cc | 10 +++---- dartsim/src/GzOdeCollisionDetector.hh | 6 ++--- dartsim/src/WorldFeatures.cc | 8 +++--- dartsim/src/WorldFeatures.hh | 6 ++--- include/gz/physics/World.hh | 10 +++---- include/gz/physics/detail/World.hh | 16 +++++------ test/common_test/simulation_features.cc | 36 ++++++++++++------------- 7 files changed, 46 insertions(+), 46 deletions(-) diff --git a/dartsim/src/GzOdeCollisionDetector.cc b/dartsim/src/GzOdeCollisionDetector.cc index 868505a20..228ee9562 100644 --- a/dartsim/src/GzOdeCollisionDetector.cc +++ b/dartsim/src/GzOdeCollisionDetector.cc @@ -52,7 +52,7 @@ bool GzOdeCollisionDetector::collide( CollisionResult *_result) { bool ret = OdeCollisionDetector::collide(_group, _option, _result); - this->LimitCollisionPairMaxTotalContacts(_result); + this->LimitCollisionPairMaxContacts(_result); return ret; } @@ -64,25 +64,25 @@ bool GzOdeCollisionDetector::collide( CollisionResult *_result) { bool ret = OdeCollisionDetector::collide(_group1, _group2, _option, _result); - this->LimitCollisionPairMaxTotalContacts(_result); + this->LimitCollisionPairMaxContacts(_result); return ret; } ///////////////////////////////////////////////// -void GzOdeCollisionDetector::SetCollisionPairMaxTotalContacts( +void GzOdeCollisionDetector::SetCollisionPairMaxContacts( std::size_t _maxContacts) { this->maxCollisionPairContacts = _maxContacts; } ///////////////////////////////////////////////// -std::size_t GzOdeCollisionDetector::GetCollisionPairMaxTotalContacts() const +std::size_t GzOdeCollisionDetector::GetCollisionPairMaxContacts() const { return this->maxCollisionPairContacts; } ///////////////////////////////////////////////// -void GzOdeCollisionDetector::LimitCollisionPairMaxTotalContacts( +void GzOdeCollisionDetector::LimitCollisionPairMaxContacts( CollisionResult *_result) { if (this->maxCollisionPairContacts == diff --git a/dartsim/src/GzOdeCollisionDetector.hh b/dartsim/src/GzOdeCollisionDetector.hh index f3859fd82..de8233e93 100644 --- a/dartsim/src/GzOdeCollisionDetector.hh +++ b/dartsim/src/GzOdeCollisionDetector.hh @@ -42,12 +42,12 @@ class GzOdeCollisionDetector : public dart::collision::OdeCollisionDetector /// objects /// \param[in] _maxContacts Maximum number of contacts between a pair of /// collision objects. - public: void SetCollisionPairMaxTotalContacts(std::size_t _maxContacts); + public: void SetCollisionPairMaxContacts(std::size_t _maxContacts); /// \brief Get the maximum number of contacts between a pair of collision /// objects /// \return Maximum number of contacts between a pair of collision objects. - public: std::size_t GetCollisionPairMaxTotalContacts() const; + public: std::size_t GetCollisionPairMaxContacts() const; /// \brief Create the GzOdeCollisionDetector @@ -60,7 +60,7 @@ class GzOdeCollisionDetector : public dart::collision::OdeCollisionDetector /// The function modifies the contacts vector inside the CollisionResult /// object to cap the number of contacts for each collision pair based on the /// maxCollisionPairContacts value - private: void LimitCollisionPairMaxTotalContacts(CollisionResult *_result); + private: void LimitCollisionPairMaxContacts(CollisionResult *_result); /// \brief Maximum number of contacts between a pair of collision objects. private: std::size_t maxCollisionPairContacts = diff --git a/dartsim/src/WorldFeatures.cc b/dartsim/src/WorldFeatures.cc index 6e6e2ea4b..da7088580 100644 --- a/dartsim/src/WorldFeatures.cc +++ b/dartsim/src/WorldFeatures.cc @@ -98,7 +98,7 @@ WorldFeatures::LinearVectorType WorldFeatures::GetWorldGravity( } ///////////////////////////////////////////////// -void WorldFeatures::SetWorldCollisionPairMaxTotalContacts( +void WorldFeatures::SetWorldCollisionPairMaxContacts( const Identity &_id, std::size_t _maxContacts) { auto world = this->ReferenceInterface(_id); @@ -110,7 +110,7 @@ void WorldFeatures::SetWorldCollisionPairMaxTotalContacts( collisionDetector); if (odeCollisionDetector) { - odeCollisionDetector->SetCollisionPairMaxTotalContacts(_maxContacts); + odeCollisionDetector->SetCollisionPairMaxContacts(_maxContacts); } else { @@ -120,7 +120,7 @@ void WorldFeatures::SetWorldCollisionPairMaxTotalContacts( } ///////////////////////////////////////////////// -std::size_t WorldFeatures::GetWorldCollisionPairMaxTotalContacts( +std::size_t WorldFeatures::GetWorldCollisionPairMaxContacts( const Identity &_id) const { auto world = this->ReferenceInterface(_id); @@ -131,7 +131,7 @@ std::size_t WorldFeatures::GetWorldCollisionPairMaxTotalContacts( collisionDetector); if (odeCollisionDetector) { - return odeCollisionDetector->GetCollisionPairMaxTotalContacts(); + return odeCollisionDetector->GetCollisionPairMaxContacts(); } return 0u; diff --git a/dartsim/src/WorldFeatures.hh b/dartsim/src/WorldFeatures.hh index 850d9439c..da15810dd 100644 --- a/dartsim/src/WorldFeatures.hh +++ b/dartsim/src/WorldFeatures.hh @@ -30,7 +30,7 @@ namespace dartsim { struct WorldFeatureList : FeatureList< CollisionDetector, - CollisionPairMaxTotalContacts, + CollisionPairMaxContacts, Gravity, Solver > { }; @@ -55,11 +55,11 @@ class WorldFeatures : public: LinearVectorType GetWorldGravity(const Identity &_id) const override; // Documentation inherited - public: void SetWorldCollisionPairMaxTotalContacts( + public: void SetWorldCollisionPairMaxContacts( const Identity &_id, std::size_t _maxContacts) override; // Documentation inherited - public: std::size_t GetWorldCollisionPairMaxTotalContacts(const Identity &_id) + public: std::size_t GetWorldCollisionPairMaxContacts(const Identity &_id) const override; // Documentation inherited diff --git a/include/gz/physics/World.hh b/include/gz/physics/World.hh index fc6deeb6d..554ca266d 100644 --- a/include/gz/physics/World.hh +++ b/include/gz/physics/World.hh @@ -131,7 +131,7 @@ namespace gz }; ///////////////////////////////////////////////// - class GZ_PHYSICS_VISIBLE CollisionPairMaxTotalContacts: + class GZ_PHYSICS_VISIBLE CollisionPairMaxContacts: public virtual Feature { /// \brief The World API for getting and setting max contacts. @@ -141,12 +141,12 @@ namespace gz /// \brief Set the maximum number of contacts allowed between two /// entities. /// \param[in] _maxContacts Maximum number of contacts. - public: void SetCollisionPairMaxTotalContacts(std::size_t _maxContacts); + public: void SetCollisionPairMaxContacts(std::size_t _maxContacts); /// \brief Set the maximum number of contacts allowed between two /// entities. /// \return Maximum number of contacts. - public: std::size_t GetCollisionPairMaxTotalContacts() const; + public: std::size_t GetCollisionPairMaxContacts() const; }; /// \private The implementation API for getting and setting max contacts. @@ -157,14 +157,14 @@ namespace gz /// contacts between two entities. /// \param[in] _id Identity of the world. /// \param[in] _maxContacts Maximum number of contacts. - public: virtual void SetWorldCollisionPairMaxTotalContacts( + public: virtual void SetWorldCollisionPairMaxContacts( const Identity &_id, std::size_t _maxContacts) = 0; /// \brief Implementation API for getting the maximum number of /// contacts between two entities. /// \param[in] _id Identity of the world. /// \param[in] _maxContacts Maximum number of contacts. - public: virtual std::size_t GetWorldCollisionPairMaxTotalContacts( + public: virtual std::size_t GetWorldCollisionPairMaxContacts( const Identity &_id) const = 0; }; }; diff --git a/include/gz/physics/detail/World.hh b/include/gz/physics/detail/World.hh index 72421e270..d5270913c 100644 --- a/include/gz/physics/detail/World.hh +++ b/include/gz/physics/detail/World.hh @@ -101,20 +101,20 @@ auto Gravity::World::GetGravity( ///////////////////////////////////////////////// template -void CollisionPairMaxTotalContacts::World::SetCollisionPairMaxTotalContacts(std::size_t _maxContacts) +void CollisionPairMaxContacts::World::SetCollisionPairMaxContacts(std::size_t _maxContacts) { - this->template Interface() - ->SetWorldCollisionPairMaxTotalContacts(this->identity, _maxContacts); + this->template Interface() + ->SetWorldCollisionPairMaxContacts(this->identity, _maxContacts); } ///////////////////////////////////////////////// template -std::size_t CollisionPairMaxTotalContacts::World:: - GetCollisionPairMaxTotalContacts() const +std::size_t CollisionPairMaxContacts::World:: + GetCollisionPairMaxContacts() const { - return this->template Interface() - ->GetWorldCollisionPairMaxTotalContacts(this->identity); + return this->template Interface() + ->GetWorldCollisionPairMaxContacts(this->identity); } ///////////////////////////////////////////////// diff --git a/test/common_test/simulation_features.cc b/test/common_test/simulation_features.cc index 63437a345..005693f05 100644 --- a/test/common_test/simulation_features.cc +++ b/test/common_test/simulation_features.cc @@ -220,53 +220,53 @@ TYPED_TEST(SimulationFeaturesContactsTest, Contacts) } // The features that an engine must have to be loaded by this loader. -struct FeaturesCollisionPairMaxTotalContacts : gz::physics::FeatureList< +struct FeaturesCollisionPairMaxContacts : gz::physics::FeatureList< gz::physics::sdf::ConstructSdfWorld, gz::physics::GetContactsFromLastStepFeature, gz::physics::ForwardStep, - gz::physics::CollisionPairMaxTotalContacts + gz::physics::CollisionPairMaxContacts > {}; template -class SimulationFeaturesCollisionPairMaxTotalContactsTest : +class SimulationFeaturesCollisionPairMaxContactsTest : public SimulationFeaturesTest{}; -using SimulationFeaturesCollisionPairMaxTotalContactsTestTypes = - ::testing::Types; -TYPED_TEST_SUITE(SimulationFeaturesCollisionPairMaxTotalContactsTest, - SimulationFeaturesCollisionPairMaxTotalContactsTestTypes); +using SimulationFeaturesCollisionPairMaxContactsTestTypes = + ::testing::Types; +TYPED_TEST_SUITE(SimulationFeaturesCollisionPairMaxContactsTest, + SimulationFeaturesCollisionPairMaxContactsTestTypes); ///////////////////////////////////////////////// -TYPED_TEST(SimulationFeaturesCollisionPairMaxTotalContactsTest, - CollisionPairMaxTotalContacts) +TYPED_TEST(SimulationFeaturesCollisionPairMaxContactsTest, + CollisionPairMaxContacts) { for (const std::string &name : this->pluginNames) { - auto world = LoadPluginAndWorld( + auto world = LoadPluginAndWorld( this->loader, name, gz::common::joinPaths(TEST_WORLD_DIR, "shapes.world")); - auto checkedOutput = StepWorld( + auto checkedOutput = StepWorld( world, true, 1).first; EXPECT_TRUE(checkedOutput); auto contacts = world->GetContactsFromLastStep(); EXPECT_EQ(std::numeric_limits::max(), - world->GetCollisionPairMaxTotalContacts()); + world->GetCollisionPairMaxContacts()); // Large box collides with other shapes EXPECT_GT(contacts.size(), 30u); - world->SetCollisionPairMaxTotalContacts(1u); - EXPECT_EQ(1u, world->GetCollisionPairMaxTotalContacts()); - checkedOutput = StepWorld( + world->SetCollisionPairMaxContacts(1u); + EXPECT_EQ(1u, world->GetCollisionPairMaxContacts()); + checkedOutput = StepWorld( world, true, 1).first; EXPECT_TRUE(checkedOutput); contacts = world->GetContactsFromLastStep(); EXPECT_EQ(4u, contacts.size()); - world->SetCollisionPairMaxTotalContacts(0u); - EXPECT_EQ(0u, world->GetCollisionPairMaxTotalContacts()); - checkedOutput = StepWorld( + world->SetCollisionPairMaxContacts(0u); + EXPECT_EQ(0u, world->GetCollisionPairMaxContacts()); + checkedOutput = StepWorld( world, true, 1).first; EXPECT_TRUE(checkedOutput);