From 7ff508d8b5779d8d27c88069450ac4a5428c9e51 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Wed, 28 Feb 2024 14:33:44 -0600 Subject: [PATCH 01/14] Require gz-math 6.13 for ign->gz transition (#601) Signed-off-by: Addisu Z. Taddese --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c4236e18d..6862813f7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -44,7 +44,7 @@ set(IGN_COMMON_VER ${ignition-common4_VERSION_MAJOR}) #-------------------------------------- # Find ignition-math -ign_find_package(ignition-math6 REQUIRED COMPONENTS eigen3) +ign_find_package(ignition-math6 REQUIRED COMPONENTS eigen3 VERSION 6.13) set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR}) #-------------------------------------- From 5076d6b29ed7ce8d7ca2a1a432feaacab65a439c Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Thu, 14 Mar 2024 13:10:23 -0500 Subject: [PATCH 02/14] Remove @mxgrey as code owner (#605) Signed-off-by: Addisu Z. Taddese --- .github/CODEOWNERS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 5534c1d87..fa88665d8 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -1,4 +1,4 @@ # More info: # https://help.github.com/en/github/creating-cloning-and-archiving-repositories/about-code-owners -* @azeey @mxgrey @scpeters +* @azeey @scpeters From 13bf7f50ce0c66d942884b502294014360190e82 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Mon, 8 Apr 2024 18:14:24 -0700 Subject: [PATCH 03/14] Disable test failing due to ODE/libccd (#621) Part of #620. Signed-off-by: Steve Peters --- test/common_test/joint_features.cc | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/test/common_test/joint_features.cc b/test/common_test/joint_features.cc index 346821bb6..68d0dbc76 100644 --- a/test/common_test/joint_features.cc +++ b/test/common_test/joint_features.cc @@ -966,9 +966,23 @@ TYPED_TEST(JointFeaturesDetachTest, JointDetach) // sanity check on velocity values EXPECT_LT(1e-5, upperLinkLinearVelocity.Z()); EXPECT_GT(-0.03, upperLinkAngularVelocity.X()); - EXPECT_NEAR(0.0, upperLinkLinearVelocity.X(), 1e-6); +#ifdef __APPLE__ + // Disable some expectations for dartsim plugin on homebrew, + // see https://github.com/gazebosim/gz-physics/issues/620. + if (this->PhysicsEngineName(name) != "dartsim") +#endif + { + EXPECT_NEAR(0.0, upperLinkLinearVelocity.X(), 1e-6); + } EXPECT_NEAR(0.0, upperLinkLinearVelocity.Y(), 1e-6); - EXPECT_NEAR(0.0, upperLinkAngularVelocity.Y(), 1e-6); +#ifdef __APPLE__ + // Disable some expectations for dartsim plugin on homebrew, + // see https://github.com/gazebosim/gz-physics/issues/620. + if (this->PhysicsEngineName(name) != "dartsim") +#endif + { + EXPECT_NEAR(0.0, upperLinkAngularVelocity.Y(), 1e-6); + } EXPECT_NEAR(0.0, upperLinkAngularVelocity.Z(), 1e-6); upperJoint->Detach(); From d0f3867ffc99c666f3bc4a405bb14abf0e703cf6 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Sat, 20 Apr 2024 10:08:09 -0700 Subject: [PATCH 04/14] Fix windows compiler warning (#629) Match comment style in harmonic. Signed-off-by: Steve Peters --- bullet-featherstone/src/Base.cc | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/bullet-featherstone/src/Base.cc b/bullet-featherstone/src/Base.cc index d157e33d8..7c230a31d 100644 --- a/bullet-featherstone/src/Base.cc +++ b/bullet-featherstone/src/Base.cc @@ -45,10 +45,10 @@ WorldInfo::WorldInfo(std::string name_) // By default a large impulse is applied when collisions penetrate // which causes unstable behavior. Bullet featherstone does not support - // configuring split impulse and penetration threshold parameters. Instead the - // penentration impulse depends on the erp2 parameter so set to a small value - // (default is 0.2). - this->world->getSolverInfo().m_erp2 = 0.002; + // configuring split impulse and penetration threshold parameters. Instead + // the penentration impulse depends on the erp2 parameter so set to a small + // value (default in bullet is 0.2). + this->world->getSolverInfo().m_erp2 = btScalar(0.002); } } // namespace bullet_featherstone From 966265bf9292abc0422063fe8d2d3db15fcdf498 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Tue, 21 May 2024 13:56:15 -0300 Subject: [PATCH 05/14] Disable test failing due to ODE/libccd (backport) (#642) Signed-off-by: Jorge Perez --- dartsim/src/JointFeatures_TEST.cc | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/dartsim/src/JointFeatures_TEST.cc b/dartsim/src/JointFeatures_TEST.cc index 2bd173c5d..d2d0a9c76 100644 --- a/dartsim/src/JointFeatures_TEST.cc +++ b/dartsim/src/JointFeatures_TEST.cc @@ -734,9 +734,17 @@ TEST_F(JointFeaturesFixture, JointDetach) // sanity check on velocity values EXPECT_LT(1e-5, upperLinkLinearVelocity.Z()); EXPECT_GT(-0.03, upperLinkAngularVelocity.X()); +#ifndef __APPLE__ + // Disable some expectations for dartsim plugin on homebrew, + // see https://github.com/gazebosim/gz-physics/issues/620. EXPECT_NEAR(0.0, upperLinkLinearVelocity.X(), 1e-6); +#endif EXPECT_NEAR(0.0, upperLinkLinearVelocity.Y(), 1e-6); +#ifndef __APPLE__ + // Disable some expectations for dartsim plugin on homebrew, + // see https://github.com/gazebosim/gz-physics/issues/620. EXPECT_NEAR(0.0, upperLinkAngularVelocity.Y(), 1e-6); +#endif EXPECT_NEAR(0.0, upperLinkAngularVelocity.Z(), 1e-6); upperJoint->Detach(); From 9a2986643b87064ad8447bb57af4db65fe52a9d8 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Mon, 20 May 2024 13:48:01 -0300 Subject: [PATCH 06/14] Disable test failing due to ODE/libccd (backport #621) Signed-off-by: Jorge Perez --- dartsim/src/JointFeatures_TEST.cc | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/dartsim/src/JointFeatures_TEST.cc b/dartsim/src/JointFeatures_TEST.cc index 9e2d49f16..7a275b89a 100644 --- a/dartsim/src/JointFeatures_TEST.cc +++ b/dartsim/src/JointFeatures_TEST.cc @@ -743,9 +743,17 @@ TEST_F(JointFeaturesFixture, JointDetach) // sanity check on velocity values EXPECT_LT(1e-5, upperLinkLinearVelocity.Z()); EXPECT_GT(-0.03, upperLinkAngularVelocity.X()); +#ifndef __APPLE__ + // Disable some expectations for dartsim plugin on homebrew, + // see https://github.com/gazebosim/gz-physics/issues/620. EXPECT_NEAR(0.0, upperLinkLinearVelocity.X(), 1e-6); +#endif EXPECT_NEAR(0.0, upperLinkLinearVelocity.Y(), 1e-6); +#ifndef __APPLE__ + // Disable some expectations for dartsim plugin on homebrew, + // see https://github.com/gazebosim/gz-physics/issues/620. EXPECT_NEAR(0.0, upperLinkAngularVelocity.Y(), 1e-6); +#endif EXPECT_NEAR(0.0, upperLinkAngularVelocity.Z(), 1e-6); upperJoint->Detach(); From 78e87e42101adefc7eb922c6d83c78896d3d6ad7 Mon Sep 17 00:00:00 2001 From: AzulRadio <50132891+AzulRadio@users.noreply.github.com> Date: Fri, 7 Jun 2024 11:38:57 -0500 Subject: [PATCH 07/14] Add no gravity link support (#633) * add no gravity link support and test for DartSim Signed-off-by: youhy * remove debug code Signed-off-by: youhy * fix test Signed-off-by: Ian Chen --------- Signed-off-by: youhy Signed-off-by: Ian Chen Co-authored-by: Ian Chen --- dartsim/src/SDFFeatures.cc | 2 ++ dartsim/src/WorldFeatures_TEST.cc | 12 ++++++++++++ dartsim/worlds/falling.world | 12 ++++++++++++ 3 files changed, 26 insertions(+) diff --git a/dartsim/src/SDFFeatures.cc b/dartsim/src/SDFFeatures.cc index 62137286e..27b8be036 100644 --- a/dartsim/src/SDFFeatures.cc +++ b/dartsim/src/SDFFeatures.cc @@ -600,6 +600,8 @@ Identity SDFFeatures::ConstructSdfLink( bodyProperties.mInertia.setLocalCOM(localCom); + bodyProperties.mGravityMode = _sdfLink.EnableGravity(); + dart::dynamics::FreeJoint::Properties jointProperties; jointProperties.mName = bodyProperties.mName + "_FreeJoint"; // TODO(MXG): Consider adding a UUID to this joint name in order to avoid any diff --git a/dartsim/src/WorldFeatures_TEST.cc b/dartsim/src/WorldFeatures_TEST.cc index 0126e2621..24a094865 100644 --- a/dartsim/src/WorldFeatures_TEST.cc +++ b/dartsim/src/WorldFeatures_TEST.cc @@ -140,6 +140,12 @@ TEST_F(WorldFeaturesFixture, Gravity) auto link = model->GetLink(0); ASSERT_NE(nullptr, link); + auto modelNoGravity = world->GetModel("sphere_no_gravity"); + ASSERT_NE(nullptr, modelNoGravity); + + auto linkNoGravity = modelNoGravity->GetLink(0); + ASSERT_NE(nullptr, linkNoGravity); + // initial link pose const Eigen::Vector3d initialLinkPosition(0, 0, 2); { @@ -190,6 +196,12 @@ TEST_F(WorldFeaturesFixture, Gravity) EXPECT_PRED_FORMAT2(vectorPredicate3, Eigen::Vector3d(0.5, 0, 2.5), pos); + // pose for link without gravity should not change + Eigen::Vector3d posNoGravity = linkNoGravity->FrameDataRelativeToWorld() + .pose.translation(); + EXPECT_PRED_FORMAT2(vectorPredicate3, + Eigen::Vector3d(10, 10, 10), + posNoGravity); } } diff --git a/dartsim/worlds/falling.world b/dartsim/worlds/falling.world index 3bae3f366..881daa5b9 100644 --- a/dartsim/worlds/falling.world +++ b/dartsim/worlds/falling.world @@ -71,5 +71,17 @@ + + + false + 10 10 10 0 0 0 + + 1 + + + 1 + + + From 914d841e5ef0cd98b043b34a27e11ab669518afd Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 11 Jun 2024 04:53:06 +0800 Subject: [PATCH 08/14] dartsim: optimize picking contact points with ODE collision detector (#584) * add test for selecting contact with max depth Signed-off-by: Ian Chen --- dartsim/src/GzOdeCollisionDetector.cc | 33 ++++++- test/common_test/Worlds.hh | 2 + test/common_test/simulation_features.cc | 94 ++++++++++++++++++- .../worlds/collision_pair_contact_point.sdf | 68 ++++++++++++++ 4 files changed, 191 insertions(+), 6 deletions(-) create mode 100644 test/common_test/worlds/collision_pair_contact_point.sdf diff --git a/dartsim/src/GzOdeCollisionDetector.cc b/dartsim/src/GzOdeCollisionDetector.cc index 228ee9562..6a81b4e06 100644 --- a/dartsim/src/GzOdeCollisionDetector.cc +++ b/dartsim/src/GzOdeCollisionDetector.cc @@ -17,6 +17,7 @@ #include #include +#include #include @@ -92,21 +93,45 @@ void GzOdeCollisionDetector::LimitCollisionPairMaxContacts( auto allContacts = _result->getContacts(); _result->clear(); + + if (this->maxCollisionPairContacts == 0u) + return; + + // A map of collision pairs and their contact info + // Contact info is stored in std::pair. The elements are: + // std::unordered_map> + std::unordered_map>> contactMap; for (auto &contact : allContacts) { - auto &count = - contactMap[contact.collisionObject1][contact.collisionObject2]; + auto &[count, lastContactIdx] = + contactMap[contact.collisionObject1][contact.collisionObject2]; count++; - auto &otherCount = + auto &[otherCount, otherLastContactIdx] = contactMap[contact.collisionObject2][contact.collisionObject1]; + std::size_t total = count + otherCount; if (total <= this->maxCollisionPairContacts) { + if (total == this->maxCollisionPairContacts) + { + lastContactIdx = _result->getNumContacts(); + otherLastContactIdx = lastContactIdx; + } _result->addContact(contact); } + else + { + // If too many contacts were generated, replace the last contact point + // of the collision pair with one that has a larger penetration depth + auto &c = _result->getContact(lastContactIdx); + if (contact.penetrationDepth > c.penetrationDepth) + { + c = contact; + } + } } } diff --git a/test/common_test/Worlds.hh b/test/common_test/Worlds.hh index 6ad145f8f..bf02f8730 100644 --- a/test/common_test/Worlds.hh +++ b/test/common_test/Worlds.hh @@ -29,6 +29,8 @@ inline std::string CommonTestWorld(const std::string &_world) namespace common_test::worlds { +const auto kCollisionPairContactPointSdf = + CommonTestWorld("collision_pair_contact_point.sdf"); const auto kContactSdf = CommonTestWorld("contact.sdf"); const auto kDetachableJointWorld = CommonTestWorld("detachable_joint.world"); const auto kEmptySdf = CommonTestWorld("empty.sdf"); diff --git a/test/common_test/simulation_features.cc b/test/common_test/simulation_features.cc index dfb657c1b..bc437b201 100644 --- a/test/common_test/simulation_features.cc +++ b/test/common_test/simulation_features.cc @@ -223,9 +223,13 @@ TYPED_TEST(SimulationFeaturesContactsTest, Contacts) // The features that an engine must have to be loaded by this loader. struct FeaturesCollisionPairMaxContacts : gz::physics::FeatureList< gz::physics::sdf::ConstructSdfWorld, - gz::physics::GetContactsFromLastStepFeature, + gz::physics::CollisionPairMaxContacts, + gz::physics::FindFreeGroupFeature, gz::physics::ForwardStep, - gz::physics::CollisionPairMaxContacts + gz::physics::FreeGroupFrameSemantics, + gz::physics::GetContactsFromLastStepFeature, + gz::physics::GetModelFromWorld, + gz::physics::SetFreeGroupWorldPose > {}; template @@ -276,6 +280,92 @@ TYPED_TEST(SimulationFeaturesCollisionPairMaxContactsTest, } } +///////////////////////////////////////////////// +TYPED_TEST(SimulationFeaturesCollisionPairMaxContactsTest, + CollisionPairMaxContactsSelection) +{ + for (const std::string &name : this->pluginNames) + { + auto world = LoadPluginAndWorld( + this->loader, + name, + common_test::worlds::kCollisionPairContactPointSdf); + auto checkedOutput = StepWorld( + world, true, 1).first; + EXPECT_TRUE(checkedOutput); + + // Verify initial pose + const gz::math::Pose3d initialPose = gz::math::Pose3d::Zero; + auto ellipsoid = world->GetModel("ellipsoid"); + ASSERT_NE(nullptr, ellipsoid); + auto ellipsoidFreeGroup = ellipsoid->FindFreeGroup(); + ASSERT_NE(nullptr, ellipsoidFreeGroup); + auto box = world->GetModel("box"); + ASSERT_NE(nullptr, box); + auto boxFreeGroup = box->FindFreeGroup(); + ASSERT_NE(nullptr, boxFreeGroup); + auto ellipsoidFrameData = ellipsoidFreeGroup->FrameDataRelativeToWorld(); + auto boxFrameData = boxFreeGroup->FrameDataRelativeToWorld(); + EXPECT_EQ(initialPose, + gz::math::eigen3::convert(ellipsoidFrameData.pose)); + EXPECT_EQ(initialPose, + gz::math::eigen3::convert(boxFrameData.pose)); + + // Get all contacts between box and ellipsoid + auto contacts = world->GetContactsFromLastStep(); + EXPECT_EQ(std::numeric_limits::max(), + world->GetCollisionPairMaxContacts()); + EXPECT_GT(contacts.size(), 30u); + + // Find contact point with max penetration depth + double maxDepth = 0; + for (const auto &contact : contacts) + { + const auto* extraContactData = + contact.template Query< + gz::physics::World3d< + FeaturesCollisionPairMaxContacts>::ExtraContactData>(); + ASSERT_NE(nullptr, extraContactData); + if (extraContactData->depth > maxDepth) + maxDepth = extraContactData->depth; + } + EXPECT_GT(maxDepth, 0.0); + + // Reset pose back to initial pose + ellipsoidFreeGroup->SetWorldPose( + gz::math::eigen3::convert(initialPose)); + boxFreeGroup->SetWorldPose( + gz::math::eigen3::convert(initialPose)); + ellipsoidFrameData = ellipsoidFreeGroup->FrameDataRelativeToWorld(); + boxFrameData = boxFreeGroup->FrameDataRelativeToWorld(); + + EXPECT_EQ(initialPose, + gz::math::eigen3::convert(ellipsoidFrameData.pose)); + EXPECT_EQ(initialPose, + gz::math::eigen3::convert(boxFrameData.pose)); + + // Set max contact between collision pairs to be 1 + world->SetCollisionPairMaxContacts(1u); + EXPECT_EQ(1u, world->GetCollisionPairMaxContacts()); + checkedOutput = StepWorld( + world, true, 1).first; + EXPECT_TRUE(checkedOutput); + + contacts = world->GetContactsFromLastStep(); + EXPECT_EQ(1u, contacts.size()); + + // Verify that the physics engine picked the contact with max penetration + // depth + auto contact = contacts[0]; + const auto* extraContactData = + contact.template Query< + gz::physics::World3d< + FeaturesCollisionPairMaxContacts>::ExtraContactData>(); + ASSERT_NE(nullptr, extraContactData); + EXPECT_FLOAT_EQ(maxDepth, extraContactData->depth); + } +} + // The features that an engine must have to be loaded by this loader. struct FeaturesStep : gz::physics::FeatureList< gz::physics::sdf::ConstructSdfWorld, diff --git a/test/common_test/worlds/collision_pair_contact_point.sdf b/test/common_test/worlds/collision_pair_contact_point.sdf new file mode 100644 index 000000000..74377d4b6 --- /dev/null +++ b/test/common_test/worlds/collision_pair_contact_point.sdf @@ -0,0 +1,68 @@ + + + + + + true + 0 0 0.0 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 100 100 1 + + + + + + + 100 100 1 + + + + + + + + 0 -0 0.0 0 0 0 + + + + 0.068 + 0 + 0 + 0.058 + 0 + 0.026 + + 1.0 + + + + + 0.2 0.3 0.5 + + + + + + + 0.2 0.3 0.5 + + + + + + + From 1fa4f63c9ed6494fb625ccc4d87b502ba9264b60 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Tue, 11 Jun 2024 21:00:58 +0200 Subject: [PATCH 09/14] Prepare for 6.6.0 MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- CMakeLists.txt | 2 +- Changelog.md | 68 ++++++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 69 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a2d1f57cc..90437bb07 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.5.1 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(gz-physics6 VERSION 6.5.1) +project(gz-physics6 VERSION 6.6.0) #============================================================================ # Find gz-cmake diff --git a/Changelog.md b/Changelog.md index 3ecde71b1..77311a2bf 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,5 +1,73 @@ ## Gazebo Physics 6.x +### Gazebo Physics 6.6.0 (2024-06-11) + +1. dartsim: optimize picking contact points with ODE collision detectorq + * [Pull request #584](https://github.com/gazebosim/gz-physics/pull/584) + +1. Fix windows compiler warning + * [Pull request #629](https://github.com/gazebosim/gz-physics/pull/629) + +1. Disable test failing due to ODE/libccd + * [Pull request #621](https://github.com/gazebosim/gz-physics/pull/621) + +1. bullet-featherstone: Improve mesh collision stability + * [Pull request #600](https://github.com/gazebosim/gz-physics/pull/600) + +1. bullet-featherstone: Support nested models + * [Pull request #574](https://github.com/gazebosim/gz-physics/pull/574) + +1. Revert "bazel: updates for garden (#513)" + * [Pull request #513)"](https://github.com/gazebosim/gz-physics/pull/513)") + +1. bazel: updates for garden + * [Pull request #513](https://github.com/gazebosim/gz-physics/pull/513) + +1. Garden test cleanup + * [Pull request #587](https://github.com/gazebosim/gz-physics/pull/587) + +1. Support setting max contacts in dartsim's ODE collision detector + * [Pull request #582](https://github.com/gazebosim/gz-physics/pull/582) + +1. Get bullet version from cmake instead of API + * [Pull request #591](https://github.com/gazebosim/gz-physics/pull/591) + +1. Prepare for 2.6.2 release + * [Pull request #585](https://github.com/gazebosim/gz-physics/pull/585) + +1. Reduce error to debug messsage for mesh construction (#531) + * [Pull request #531) (#581](https://github.com/gazebosim/gz-physics/pull/531) (#581) + +1. bullet-featherstone: Set collision spinning friction + * [Pull request #579](https://github.com/gazebosim/gz-physics/pull/579) + +1. CI workflow: use 22.04 for codecheck, coverage + * [Pull request #578](https://github.com/gazebosim/gz-physics/pull/578) + +1. Update github action workflows + * [Pull request #572](https://github.com/gazebosim/gz-physics/pull/572) + +1. dartsim: fix handling inertia matrix pose rotation + * [Pull request #351](https://github.com/gazebosim/gz-physics/pull/351) + +1. bullet-featherstone: fix setting angular velocity + * [Pull request #567](https://github.com/gazebosim/gz-physics/pull/567) + +1. bullet-featherstone: support off-diagonal inertia + * [Pull request #544](https://github.com/gazebosim/gz-physics/pull/544) + +1. bullet-featherstoneFix how links are flattened in ConstructSdfModel + * [Pull request #562](https://github.com/gazebosim/gz-physics/pull/562) + +1. Add sample ctest cmds to tutorial + * [Pull request #566](https://github.com/gazebosim/gz-physics/pull/566) + +1. Add a test to verify behavior of detachable joints + * [Pull request #563](https://github.com/gazebosim/gz-physics/pull/563) + +1. Use correct link indicies when constructing fixed constraints + * [Pull request #530](https://github.com/gazebosim/gz-physics/pull/530) + ### Gazebo Physics 6.5.1 (2023-09-26) 1. joint_features test: reduce console spam From 804a3ef4532f1b0000686ea8f0aca56b3f9780de Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 12 Jun 2024 17:20:40 +0200 Subject: [PATCH 10/14] Tweaks MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- Changelog.md | 14 +++----------- 1 file changed, 3 insertions(+), 11 deletions(-) diff --git a/Changelog.md b/Changelog.md index 77311a2bf..b24a33a0d 100644 --- a/Changelog.md +++ b/Changelog.md @@ -20,9 +20,6 @@ 1. Revert "bazel: updates for garden (#513)" * [Pull request #513)"](https://github.com/gazebosim/gz-physics/pull/513)") -1. bazel: updates for garden - * [Pull request #513](https://github.com/gazebosim/gz-physics/pull/513) - 1. Garden test cleanup * [Pull request #587](https://github.com/gazebosim/gz-physics/pull/587) @@ -32,19 +29,14 @@ 1. Get bullet version from cmake instead of API * [Pull request #591](https://github.com/gazebosim/gz-physics/pull/591) -1. Prepare for 2.6.2 release - * [Pull request #585](https://github.com/gazebosim/gz-physics/pull/585) - -1. Reduce error to debug messsage for mesh construction (#531) - * [Pull request #531) (#581](https://github.com/gazebosim/gz-physics/pull/531) (#581) +1. Reduce error to debug messsage for mesh construction (#581) + * [Pull request #581)(https://github.com/gazebosim/gz-physics/pull/581) 1. bullet-featherstone: Set collision spinning friction * [Pull request #579](https://github.com/gazebosim/gz-physics/pull/579) -1. CI workflow: use 22.04 for codecheck, coverage +1. Infrastructure * [Pull request #578](https://github.com/gazebosim/gz-physics/pull/578) - -1. Update github action workflows * [Pull request #572](https://github.com/gazebosim/gz-physics/pull/572) 1. dartsim: fix handling inertia matrix pose rotation From 72f9d9bad085fd4fbaba8b3842f431d4b907b1f0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 12 Jun 2024 18:24:33 +0200 Subject: [PATCH 11/14] Update Changelog.md MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Ian Chen Signed-off-by: Carlos Agüero --- Changelog.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Changelog.md b/Changelog.md index b24a33a0d..ccc9955d6 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2,7 +2,7 @@ ### Gazebo Physics 6.6.0 (2024-06-11) -1. dartsim: optimize picking contact points with ODE collision detectorq +1. dartsim: optimize picking contact points with ODE collision detector * [Pull request #584](https://github.com/gazebosim/gz-physics/pull/584) 1. Fix windows compiler warning From c219b452a98f1f59ced91889d5632d9991556b23 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 12 Jun 2024 18:24:41 +0200 Subject: [PATCH 12/14] Update Changelog.md MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Ian Chen Signed-off-by: Carlos Agüero --- Changelog.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Changelog.md b/Changelog.md index ccc9955d6..285c81eb9 100644 --- a/Changelog.md +++ b/Changelog.md @@ -18,7 +18,7 @@ * [Pull request #574](https://github.com/gazebosim/gz-physics/pull/574) 1. Revert "bazel: updates for garden (#513)" - * [Pull request #513)"](https://github.com/gazebosim/gz-physics/pull/513)") + * [Pull request #513](https://github.com/gazebosim/gz-physics/pull/513) 1. Garden test cleanup * [Pull request #587](https://github.com/gazebosim/gz-physics/pull/587) From bddd5eccccefcf6a0f8fb4ecb24847b75be4c264 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 12 Jun 2024 18:24:47 +0200 Subject: [PATCH 13/14] Update Changelog.md MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Ian Chen Signed-off-by: Carlos Agüero --- Changelog.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Changelog.md b/Changelog.md index 285c81eb9..60a86058e 100644 --- a/Changelog.md +++ b/Changelog.md @@ -48,7 +48,7 @@ 1. bullet-featherstone: support off-diagonal inertia * [Pull request #544](https://github.com/gazebosim/gz-physics/pull/544) -1. bullet-featherstoneFix how links are flattened in ConstructSdfModel +1. bullet-featherstone: Fix how links are flattened in ConstructSdfModel * [Pull request #562](https://github.com/gazebosim/gz-physics/pull/562) 1. Add sample ctest cmds to tutorial From ddcba9d66669d246309d8d6670a5b105f7b2853b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 12 Jun 2024 18:24:53 +0200 Subject: [PATCH 14/14] Update Changelog.md MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Ian Chen Signed-off-by: Carlos Agüero --- Changelog.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Changelog.md b/Changelog.md index 60a86058e..de4611780 100644 --- a/Changelog.md +++ b/Changelog.md @@ -30,7 +30,7 @@ * [Pull request #591](https://github.com/gazebosim/gz-physics/pull/591) 1. Reduce error to debug messsage for mesh construction (#581) - * [Pull request #581)(https://github.com/gazebosim/gz-physics/pull/581) + * [Pull request #581](https://github.com/gazebosim/gz-physics/pull/581) 1. bullet-featherstone: Set collision spinning friction * [Pull request #579](https://github.com/gazebosim/gz-physics/pull/579)