From 3bf2bb0a4ef80c4bca62c9f3d80403eeb59a7e24 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Mon, 15 Mar 2021 20:22:26 -0700 Subject: [PATCH 1/4] Set collision detector and solver from SDF Signed-off-by: Louise Poubel --- examples/worlds/physics_options.sdf | 173 ++++++++++++++++++ include/ignition/gazebo/components/Physics.hh | 17 ++ src/LevelManager.cc | 28 +++ src/SdfEntityCreator.cc | 28 +++ .../component_inspector/ComponentInspector.cc | 31 ++++ src/systems/physics/Physics.cc | 45 ++++- src/systems/physics/Physics.hh | 1 + test/integration/physics_system.cc | 44 +++++ test/worlds/physics_options.sdf | 17 ++ 9 files changed, 383 insertions(+), 1 deletion(-) create mode 100644 examples/worlds/physics_options.sdf create mode 100644 test/worlds/physics_options.sdf diff --git a/examples/worlds/physics_options.sdf b/examples/worlds/physics_options.sdf new file mode 100644 index 0000000000..a02c603296 --- /dev/null +++ b/examples/worlds/physics_options.sdf @@ -0,0 +1,173 @@ + + + + + + 0.001 + 1.0 + + bullet + + pgs + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + 0 0 -0.5 0 -0.52 0 + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0.5 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + 0 -1.5 0.5 1.57079632679 0 0 + + + + 2 + 0 + 0 + 2 + 0 + 2 + + 2.0 + + + + + 0.5 + 1.0 + + + + + + + + 0.5 + 1.0 + + + + 0 1 0 1 + 0 1 0 1 + 0 1 0 1 + + + + + + + 0 1.5 0.5 0 0 0 + + + + 3 + 0 + 0 + 3 + 0 + 3 + + 3.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + + + + diff --git a/include/ignition/gazebo/components/Physics.hh b/include/ignition/gazebo/components/Physics.hh index 804059dedc..117c258367 100644 --- a/include/ignition/gazebo/components/Physics.hh +++ b/include/ignition/gazebo/components/Physics.hh @@ -17,6 +17,8 @@ #ifndef IGNITION_GAZEBO_COMPONENTS_PHYSICS_HH_ #define IGNITION_GAZEBO_COMPONENTS_PHYSICS_HH_ +#include + #include #include @@ -48,6 +50,21 @@ namespace components serializers::PhysicsSerializer>; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Physics", Physics) + + /// \brief The name of the collision detector to be used. The supported + /// options will depend on the physics engine being used. + using PhysicsCollisionDetector = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.PhysicsCollisionDetector", + PhysicsCollisionDetector) + + /// \brief The name of the solver to be used. The supported options will + /// depend on the physics engine being used. + using PhysicsSolver = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PhysicsSolver", + PhysicsSolver) } } } diff --git a/src/LevelManager.cc b/src/LevelManager.cc index 74e2f71020..4c5beba7e6 100644 --- a/src/LevelManager.cc +++ b/src/LevelManager.cc @@ -111,6 +111,34 @@ void LevelManager::ReadLevelPerformerInfo() 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()) + { + if (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())); diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index 8503d4ab92..bb0103f457 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -239,6 +239,34 @@ Entity SdfEntityCreator::CreateEntities(const sdf::World *_world) this->dataPtr->ecm->CreateComponent(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()) + { + if (physics->Element()->HasElement("dart")) + { + auto dartElem = physics->Element()->GetElement("dart"); + + if (dartElem->HasElement("collision_detector")) + { + auto collisionDetector = + dartElem->Get("collision_detector"); + + this->dataPtr->ecm->CreateComponent(worldEntity, + components::PhysicsCollisionDetector(collisionDetector)); + } + if (dartElem->HasElement("solver") && + dartElem->GetElement("solver")->HasElement("solver_type")) + { + auto solver = + dartElem->GetElement("solver")->Get("solver_type"); + + this->dataPtr->ecm->CreateComponent(worldEntity, + components::PhysicsSolver(solver)); + } + } + } + // MagneticField this->dataPtr->ecm->CreateComponent(worldEntity, components::MagneticField(_world->MagneticField())); diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 4467419161..d42dad16ff 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -49,8 +49,11 @@ #include "ignition/gazebo/components/Performer.hh" #include "ignition/gazebo/components/PerformerAffinity.hh" #include "ignition/gazebo/components/Physics.hh" +#include "ignition/gazebo/components/PhysicsEnginePlugin.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/PoseCmd.hh" +#include "ignition/gazebo/components/RenderEngineGuiPlugin.hh" +#include "ignition/gazebo/components/RenderEngineServerPlugin.hh" #include "ignition/gazebo/components/SelfCollide.hh" #include "ignition/gazebo/components/Sensor.hh" #include "ignition/gazebo/components/SourceFilePath.hh" @@ -601,12 +604,40 @@ void ComponentInspector::Update(const UpdateInfo &, if (comp) setData(item, comp->Data()); } + else if (typeId == components::PhysicsCollisionDetector::typeId) + { + auto comp = _ecm.Component( + this->dataPtr->entity); + if (comp) + setData(item, comp->Data()); + } + else if (typeId == components::PhysicsSolver::typeId) + { + auto comp = _ecm.Component( + this->dataPtr->entity); + if (comp) + setData(item, comp->Data()); + } else if (typeId == components::Pose::typeId) { auto comp = _ecm.Component(this->dataPtr->entity); if (comp) setData(item, comp->Data()); } + else if (typeId == components::RenderEngineGuiPlugin::typeId) + { + auto comp = _ecm.Component( + this->dataPtr->entity); + if (comp) + setData(item, comp->Data()); + } + else if (typeId == components::RenderEngineServerPlugin::typeId) + { + auto comp = _ecm.Component( + this->dataPtr->entity); + if (comp) + setData(item, comp->Data()); + } else if (typeId == components::Static::typeId) { auto comp = _ecm.Component(this->dataPtr->entity); diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 1f5cae843a..23132b2666 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -55,6 +55,7 @@ #include #include #include +#include #include #include #include @@ -110,6 +111,7 @@ #include "ignition/gazebo/components/ParentLinkName.hh" #include "ignition/gazebo/components/ExternalWorldWrenchCmd.hh" #include "ignition/gazebo/components/JointForceCmd.hh" +#include "ignition/gazebo/components/Physics.hh" #include "ignition/gazebo/components/PhysicsEnginePlugin.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/PoseCmd.hh" @@ -355,6 +357,12 @@ class ignition::gazebo::systems::PhysicsPrivate CollisionFeatureList, physics::mesh::AttachMeshShapeFeature>{}; + ////////////////////////////////////////////////// + // Physics options + /// \brief Feature list for setting and getting physics options + public: struct PhysicsOptionsFeatureList : ignition::physics::FeatureList< + ignition::physics::PhysicsOptions>{}; + ////////////////////////////////////////////////// // Nested Models @@ -369,7 +377,8 @@ class ignition::gazebo::systems::PhysicsPrivate physics::World, MinimumFeatureList, CollisionFeatureList, - NestedModelFeatureList>; + NestedModelFeatureList, + PhysicsOptionsFeatureList>; /// \brief A map between world entity ids in the ECM to World Entities in /// ign-physics. @@ -613,6 +622,40 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) auto worldPtrPhys = this->engine->ConstructWorld(world); this->entityWorldMap.AddEntity(_entity, worldPtrPhys); + // Optional world features + auto collisionDetectorComp = + _ecm.Component(_entity); + auto solverComp = _ecm.Component(_entity); + if (collisionDetectorComp || solverComp) + { + auto physicsOptionsFeature = + this->entityWorldMap.EntityCast( + _entity); + if (!physicsOptionsFeature) + { + static bool informed{false}; + if (!informed) + { + igndbg << "Attempting to set physics options, but the " + << "phyiscs engine doesn't support feature " + << "[PhysicsOptionsFeature]. Options will be ignored." + << std::endl; + informed = true; + } + return true; + } + + if (collisionDetectorComp) + { + physicsOptionsFeature->SetCollisionDetector( + collisionDetectorComp->Data()); + } + if (solverComp) + { + physicsOptionsFeature->SetSolver(solverComp->Data()); + } + } + return true; }); diff --git a/src/systems/physics/Physics.hh b/src/systems/physics/Physics.hh index 38f7f10599..6b34c19263 100644 --- a/src/systems/physics/Physics.hh +++ b/src/systems/physics/Physics.hh @@ -37,6 +37,7 @@ #include #include #include +#include #include #include #include diff --git a/test/integration/physics_system.cc b/test/integration/physics_system.cc index 39ce38fab0..15ed2e05c3 100644 --- a/test/integration/physics_system.cc +++ b/test/integration/physics_system.cc @@ -51,6 +51,7 @@ #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/ParentEntity.hh" +#include "ignition/gazebo/components/Physics.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/Static.hh" #include "ignition/gazebo/components/Visual.hh" @@ -1271,3 +1272,46 @@ TEST_F(PhysicsSystemFixture, IncludeNestedModelTPE) ASSERT_NE(parents.end(), parentIt); EXPECT_EQ("model_01", parentIt->second); } + +///////////////////////////////////////////////// +TEST_F(PhysicsSystemFixture, PhysicsOptions) +{ + ignition::gazebo::ServerConfig serverConfig; + serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/physics_options.sdf"); + + bool checked{false}; + + // Create a system to check components + test::Relay testSystem; + testSystem.OnPostUpdate( + [&checked](const gazebo::UpdateInfo &, + const gazebo::EntityComponentManager &_ecm) + { + _ecm.Each( + [&](const ignition::gazebo::Entity &, const components::World *, + const components::PhysicsCollisionDetector *_collisionDetector, + const components::PhysicsSolver *_solver)->bool + { + EXPECT_NE(nullptr, _collisionDetector); + if (_collisionDetector) + { + EXPECT_EQ("bullet", _collisionDetector->Data()); + } + EXPECT_NE(nullptr, _solver); + if (_solver) + { + EXPECT_EQ("pgs", _solver->Data()); + } + checked = true; + return true; + }); + }); + + gazebo::Server server(serverConfig); + server.AddSystem(testSystem.systemPtr); + server.Run(true, 1, false); + + EXPECT_TRUE(checked); +} diff --git a/test/worlds/physics_options.sdf b/test/worlds/physics_options.sdf new file mode 100644 index 0000000000..d4fcae60e1 --- /dev/null +++ b/test/worlds/physics_options.sdf @@ -0,0 +1,17 @@ + + + + + + bullet + + pgs + + + + + + + From 0fa838a9dae68c12e62332b96c19c110ada6b834 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 23 Mar 2021 21:05:51 -0700 Subject: [PATCH 2/4] Split into separate features Signed-off-by: Louise Poubel --- src/systems/physics/Physics.cc | 59 ++++++++++++++++++++++++---------- 1 file changed, 42 insertions(+), 17 deletions(-) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index fb8622e3fd..ddf704bffb 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -363,10 +363,16 @@ class ignition::gazebo::systems::PhysicsPrivate physics::mesh::AttachMeshShapeFeature>{}; ////////////////////////////////////////////////// - // Physics options - /// \brief Feature list for setting and getting physics options - public: struct PhysicsOptionsFeatureList : ignition::physics::FeatureList< - ignition::physics::PhysicsOptions>{}; + // Collision detector + /// \brief Feature list for setting and getting the collision detector + public: struct CollisionDetectorFeatureList : ignition::physics::FeatureList< + ignition::physics::CollisionDetector>{}; + + ////////////////////////////////////////////////// + // Solver + /// \brief Feature list for setting and getting the solver + public: struct SolverFeatureList : ignition::physics::FeatureList< + ignition::physics::Solver>{}; ////////////////////////////////////////////////// // Nested Models @@ -383,7 +389,8 @@ class ignition::gazebo::systems::PhysicsPrivate MinimumFeatureList, CollisionFeatureList, NestedModelFeatureList, - PhysicsOptionsFeatureList>; + CollisionDetectorFeatureList, + SolverFeatureList>; /// \brief A map between world entity ids in the ECM to World Entities in /// ign-physics. @@ -630,34 +637,52 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) // Optional world features auto collisionDetectorComp = _ecm.Component(_entity); - auto solverComp = _ecm.Component(_entity); - if (collisionDetectorComp || solverComp) + if (collisionDetectorComp) { - auto physicsOptionsFeature = - this->entityWorldMap.EntityCast( + auto collisionDetectorFeature = + this->entityWorldMap.EntityCast( _entity); - if (!physicsOptionsFeature) + if (!collisionDetectorFeature) { static bool informed{false}; if (!informed) { igndbg << "Attempting to set physics options, but the " << "phyiscs engine doesn't support feature " - << "[PhysicsOptionsFeature]. Options will be ignored." + << "[CollisionDetectorFeature]. Options will be ignored." << std::endl; informed = true; } - return true; } - - if (collisionDetectorComp) + else { - physicsOptionsFeature->SetCollisionDetector( + collisionDetectorFeature->SetCollisionDetector( collisionDetectorComp->Data()); } - if (solverComp) + } + + auto solverComp = + _ecm.Component(_entity); + if (solverComp) + { + auto solverFeature = + this->entityWorldMap.EntityCast( + _entity); + if (!solverFeature) + { + static bool informed{false}; + if (!informed) + { + igndbg << "Attempting to set physics options, but the " + << "phyiscs engine doesn't support feature " + << "[SolverFeature]. Options will be ignored." + << std::endl; + informed = true; + } + } + else { - physicsOptionsFeature->SetSolver(solverComp->Data()); + solverFeature->SetSolver(solverComp->Data()); } } From 144adfbfb132003179fedc527e590bf67d4e6617 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 14 May 2021 15:03:24 -0700 Subject: [PATCH 3/4] Default options on components Signed-off-by: Louise Poubel --- src/LevelManager.cc | 35 ++++++++++------------ src/SdfEntityCreator.cc | 39 ++++++++++++------------- src/systems/physics/Physics.cc | 36 +++++++++++++++++++++++ test/integration/physics_system.cc | 47 ++++++++++++++++++++++++++++-- 4 files changed, 114 insertions(+), 43 deletions(-) diff --git a/src/LevelManager.cc b/src/LevelManager.cc index 4c5beba7e6..1b4d2f39d2 100644 --- a/src/LevelManager.cc +++ b/src/LevelManager.cc @@ -113,29 +113,26 @@ void LevelManager::ReadLevelPerformerInfo() // Populate physics options that aren't accessible outside the Element() // See https://github.com/osrf/sdformat/issues/508 - if (physics->Element()) + if (physics->Element() && physics->Element()->HasElement("dart")) { - if (physics->Element()->HasElement("dart")) - { - auto dartElem = physics->Element()->GetElement("dart"); + auto dartElem = physics->Element()->GetElement("dart"); - if (dartElem->HasElement("collision_detector")) - { - auto collisionDetector = - dartElem->Get("collision_detector"); + 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::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(worldEntity, + components::PhysicsSolver(solver)); } } diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index d54de22b9b..7c6e1be90a 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -281,29 +281,26 @@ Entity SdfEntityCreator::CreateEntities(const sdf::World *_world) // Populate physics options that aren't accessible outside the Element() // See https://github.com/osrf/sdformat/issues/508 - if (physics->Element()) + if (physics->Element() && physics->Element()->HasElement("dart")) { - if (physics->Element()->HasElement("dart")) + auto dartElem = physics->Element()->GetElement("dart"); + + if (dartElem->HasElement("collision_detector")) { - auto dartElem = physics->Element()->GetElement("dart"); - - if (dartElem->HasElement("collision_detector")) - { - auto collisionDetector = - dartElem->Get("collision_detector"); - - this->dataPtr->ecm->CreateComponent(worldEntity, - components::PhysicsCollisionDetector(collisionDetector)); - } - if (dartElem->HasElement("solver") && - dartElem->GetElement("solver")->HasElement("solver_type")) - { - auto solver = - dartElem->GetElement("solver")->Get("solver_type"); - - this->dataPtr->ecm->CreateComponent(worldEntity, - components::PhysicsSolver(solver)); - } + auto collisionDetector = + dartElem->Get("collision_detector"); + + this->dataPtr->ecm->CreateComponent(worldEntity, + components::PhysicsCollisionDetector(collisionDetector)); + } + if (dartElem->HasElement("solver") && + dartElem->GetElement("solver")->HasElement("solver_type")) + { + auto solver = + dartElem->GetElement("solver")->Get("solver_type"); + + this->dataPtr->ecm->CreateComponent(worldEntity, + components::PhysicsSolver(solver)); } } diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index c345704285..b94959e7fe 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -1873,6 +1873,42 @@ void PhysicsPrivate::UpdateSim(EntityComponentManager &_ecm, { IGN_PROFILE("PhysicsPrivate::UpdateSim"); + // Populate world components with default values + _ecm.EachNew( + [&](const Entity &_entity, + const components::World *)->bool + { + // If not provided by ECM, create component with values from physics if + // those features are available + auto collisionDetectorComp = + _ecm.Component(_entity); + if (!collisionDetectorComp) + { + auto collisionDetectorFeature = + this->entityWorldMap.EntityCast( + _entity); + if (collisionDetectorFeature) + { + _ecm.CreateComponent(_entity, components::PhysicsCollisionDetector( + collisionDetectorFeature->GetCollisionDetector())); + } + } + + auto solverComp = _ecm.Component(_entity); + if (!solverComp) + { + auto solverFeature = + this->entityWorldMap.EntityCast(_entity); + if (solverFeature) + { + _ecm.CreateComponent(_entity, + components::PhysicsSolver(solverFeature->GetSolver())); + } + } + + return true; + }); + IGN_PROFILE_BEGIN("Models"); _ecm.Each( diff --git a/test/integration/physics_system.cc b/test/integration/physics_system.cc index c23e9f6276..4b7cece9bd 100644 --- a/test/integration/physics_system.cc +++ b/test/integration/physics_system.cc @@ -473,7 +473,7 @@ TEST_F(PhysicsSystemFixture, SetFrictionCoefficient) test::Relay testSystem; testSystem.OnPostUpdate( - [&boxParams, &poses](const gazebo::UpdateInfo &_info, + [&boxParams, &poses](const gazebo::UpdateInfo &, const gazebo::EntityComponentManager &_ecm) { _ecm.Each( @@ -1335,12 +1335,53 @@ TEST_F(PhysicsSystemFixture, NestedModelIndividualCanonicalLinks) EXPECT_NEAR(zExpected, modelIt->second.Z(), 1e-2); } +///////////////////////////////////////////////// +TEST_F(PhysicsSystemFixture, DefaultPhysicsOptions) +{ + ignition::gazebo::ServerConfig serverConfig; + + bool checked{false}; + + // Create a system to check components + test::Relay testSystem; + testSystem.OnPostUpdate( + [&checked](const gazebo::UpdateInfo &, + const gazebo::EntityComponentManager &_ecm) + { + _ecm.Each( + [&](const ignition::gazebo::Entity &, const components::World *, + const components::PhysicsCollisionDetector *_collisionDetector, + const components::PhysicsSolver *_solver)->bool + { + EXPECT_NE(nullptr, _collisionDetector); + if (_collisionDetector) + { + EXPECT_EQ("ode", _collisionDetector->Data()); + } + EXPECT_NE(nullptr, _solver); + if (_solver) + { + EXPECT_EQ("DantzigBoxedLcpSolver", _solver->Data()); + } + checked = true; + return true; + }); + }); + + gazebo::Server server(serverConfig); + server.AddSystem(testSystem.systemPtr); + server.Run(true, 1, false); + + EXPECT_TRUE(checked); +} + ///////////////////////////////////////////////// TEST_F(PhysicsSystemFixture, PhysicsOptions) { ignition::gazebo::ServerConfig serverConfig; - serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/physics_options.sdf"); + serverConfig.SetSdfFile(common::joinPaths(std::string(PROJECT_SOURCE_PATH), + "test", "worlds", "physics_options.sdf")); bool checked{false}; From 16b1af45e56b021fb303236a6d62e33a247f2e39 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Wed, 16 Jun 2021 12:14:40 -0700 Subject: [PATCH 4/4] Document physics options. Signed-off-by: Louise Poubel --- tutorials/physics.md | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/tutorials/physics.md b/tutorials/physics.md index c86ecb07a7..4ff2a32097 100644 --- a/tutorials/physics.md +++ b/tutorials/physics.md @@ -84,6 +84,18 @@ serverConfig.SetPhysicsEngine("CustomEngine"); ignition::gazebo::Server server(serverConfig); ``` +## Engine configuration + +Gazebo supports the following physics engine configurations through SDF. +These options are available to all physics engines, but not all engines +may support them. The default physics engine, DART, supports all these options. + +* [//physics/dart/collision_detector](http://sdformat.org/spec?ver=1.8&elem=physics#dart_collision_detector) + * Options supported by DART: `ode` (default), `bullet`, `fcl`, `dart`. + +* [//physics/dart/solver/solver_type](http://sdformat.org/spec?ver=1.8&elem=physics#solver_solver_type) + * Options supported by DART: `dantzig` (default), `pgs` + ## Troubleshooting > Failed to find plugin [libCustomEngine.so]. Have you checked the