From 1ad8bd4ab68ce31acf5d62903092f61bbf593883 Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Fri, 13 Sep 2024 11:40:14 -0700 Subject: [PATCH 1/8] Remove unreferenced switching-physics-engine tutorial and fix broken link in 04_physics_engines Signed-off-by: Shameek Ganguly --- tutorials/04-switching-physics-engines.md | 136 ---------------------- tutorials/04_physics_engines.md | 2 +- 2 files changed, 1 insertion(+), 137 deletions(-) delete mode 100644 tutorials/04-switching-physics-engines.md diff --git a/tutorials/04-switching-physics-engines.md b/tutorials/04-switching-physics-engines.md deleted file mode 100644 index 0876a82ad..000000000 --- a/tutorials/04-switching-physics-engines.md +++ /dev/null @@ -1,136 +0,0 @@ -\page switchphysicsengines Switching physics engines - -This tutorial describes how to switch between physics engines in Gazebo Physics -when using Gazebo. -Gazebo Physics enables Gazebo to choose flexibly what physics engine -to use at runtime. -By default, Gazebo uses the [DART](https://dartsim.github.io/) physics -engine. - -Downstream developers may also integrate other physics engines by creating new -Gazebo Physics engine plugins. -See \ref tutorials "Gazebo Physics'" tutorials to learn how to integrate a -new engine. - -## How Gazebo finds physics engines - -Gazebo automatically looks for all physics engine plugins that are -installed with Gazebo Physics. -At the time of writing, there are three physics engines available (more detail -in \ref physicsplugin "Physics plugin tutorial"): -- **DART**: `gz-physics-dartsim-plugin`. -- **TPE**: `gz-physics-tpe-plugin`. -- **Bullet**: `gz-physics-bullet-plugin`. - -If you've created a custom engine plugin, you can tell Gazebo where to -find it by setting the `GZ_SIM_PHYSICS_ENGINE_PATH` environment variable to -the directory where the plugin's shared library can be found. - -For example, if you've created the following physics engine shared library on Linux: - -`/home/physics_engines/libCustomEngine.so` - -You should set the variable as follows: - -```bash -export GZ_SIM_PHYSICS_ENGINE_PATH=/home/physics_engines -``` - -If you have several libraries installed in different paths, you can add more -paths separated by a colon, for example: - -```bash -export GZ_SIM_PHYSICS_ENGINE_PATH=/home/physics_engines:/home/more_engines -``` - -For additional environment variables that Gazebo finds other plugins -or resources, you can see them by: - -```bash -gz sim -h -``` - -## Pointing Gazebo to physics engines - -There are a few different ways of telling Gazebo which engine to load. - -In any way, the standard naming for your plugin's shared library is to have a -`lib` prefix and the file extension. -Following this naming convention, the name should be `libCustomEngine.so` but -the `CustomEngine` could also work. - -### From SDF - -You can specify in Gazebo which engine to load from the SDF world file -by giving the shared library name to the `Physics` plugin tag. -For the example above, you can load it like this: - -```{.xml} - - - CustomEngine - - -``` - -### From the command line - -Alternatively, you can choose a plugin from the command line using the -`--physics-engine` option, for example: - -```bash -gz sim --physics-engine CustomEngine -``` - -### From C++ API - -All features available through the command line are also available through -[gz::sim::ServerConfig](https://gazebosim.org/api/sim/9/classgz_1_1sim_1_1ServerConfig.html). -When instantiating a server programmatically, a physics engine can be passed to -the constructor, for example: - -``` -gz::sim::ServerConfig serverConfig; -serverConfig.SetPhysicsEngine("CustomEngine"); - -gz::sim::Server server(serverConfig); -``` - -## Troubleshooting -These are common error messages that you may encounter: - -```{.bash} -Failed to find plugin [libCustomEngine.so]. Have you checked the GZ_SIM_PHYSICS_ENGINE_PATH environment variable? -``` - -Gazebo can't find out where `libCustomEngine.so` is located. - -If that's an engine you believe should be installed with Gazebo Physics, -check if the relevant plugin is installed. - -If that's a 3rd party engine, find where the `.so` file is installed and add -that path to the environment variable as described above. - -```{.bash} -Unable to load the [/home/physics_engines/libCustomEngine.so] library. -``` - -There was some problem loading that file. Check that it exists, that you have -permissions to access it, and that it's a physics engine plugin. - -```{.bash} -No plugins with all required features found in library [/home/physics_engines/libCustomEngine.so] -``` - -This means that there are plugins on that library, but none of them satisfies -the minimum requirement of features needed to run a Gazebo simulation. -Be sure to implement all the necessary features. - -```{.bash} -Failed to load a valid physics engine from [/home/physics_engines/libCustomEngine.so] -``` - -Some engines were found in that library, but none of them could be loaded. -Check that the engines implement all the necessary features. diff --git a/tutorials/04_physics_engines.md b/tutorials/04_physics_engines.md index 6ca189dec..f8c3f44a7 100644 --- a/tutorials/04_physics_engines.md +++ b/tutorials/04_physics_engines.md @@ -1,3 +1,3 @@ \page physicsengine Use different physics engines -See [Physics engines tutorial](https://gazebosim.org/api/gazebo/3.8/physics.html) in Gazebo. +See [Physics engines tutorial](https://gazebosim.org/api/sim/9/physics.html) in Gazebo. From c756d08e17f072c88252f13f3b46faf1ecc39f0f Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Fri, 13 Sep 2024 17:22:51 -0700 Subject: [PATCH 2/8] Update physics plugins tutorial to mention Bullet plugins and drop incomplete references to featurelists for individual plugins Signed-off-by: Shameek Ganguly --- tutorials/03_physics_plugins.md | 94 +++++++-------------------------- 1 file changed, 19 insertions(+), 75 deletions(-) diff --git a/tutorials/03_physics_plugins.md b/tutorials/03_physics_plugins.md index fabc8d165..b382341a4 100644 --- a/tutorials/03_physics_plugins.md +++ b/tutorials/03_physics_plugins.md @@ -1,19 +1,15 @@ \page physicsplugin Understanding the Physics Plugin -This is an introduction to different physics engines and how they are integrated into the Gazebo Physics library. - -## Gazebo Physics - -The \ref gz::physics "Gazebo Physics" library integrates external physics engines into the Gazebo Simulation eco-system. -It allows users to select from multiple supported physics engines based on their simulation needs. -Its plugin interface loads physics engines with requested features at runtime. +The \ref gz::physics "Gazebo Physics" library integrates physics engines into the Gazebo Simulation eco-system. +Each physics engine is wrapped into a Gazebo Physics Plugin that can be loaded in a Gazebo simulation. +The Physics Plugin interface loads physics engines with the requested features at runtime. It is also possible to integrate your own selected physics engine by writing a compatible plugin interface. To get a more in-depth understanding of how the physics plugin works in Gazebo, we will start with some high level concepts and definitions. -### High Level Concept +## High Level Concept Conceptually, the physics plugin can be viewed from two sides of its interface: user vs. implementation. @@ -22,7 +18,7 @@ The interface is made possible through the \ref gz::plugin "Gazebo Plugin" libra This "user side interface" makes the Gazebo Physics library "callable" from other Gazebo libraries. The implementation side interface handles specific implementations of each `Feature`. -Depending on what external physics engine we are using (DART, TPE etc.), the interface might be different. +Depending on what physics engine we are using in the plugin (DART, TPE etc.), the interface might be different. This interface is more internal facing, i.e. used mostly inside the Gazebo Physics library. The implementation of the physics plugin revolves around four key elements. @@ -38,7 +34,7 @@ The implementation of the physics plugin revolves around four key elements. FeaturePolicy is a "policy class" used to provide metadata to features about what kind of simulation engine they are going to be used in. Many physics simulations software libraries model 3-dimensional systems, though some (like Box2d) only consider 2-dimensional systems. A FeaturePolicy is used to customize Gazebo Physics' APIs by the number of dimensions (2 or 3) and also the floating point scalar type (float or double). - Dartsim and TPE reference implementations both use FeaturePolicy3d (3 dimensions, double). + (All of the currently supported physics engine use FeaturePolicy3d i.e. 3 dimensions and double.) 3. \ref gz::physics::Feature "Feature" @@ -52,10 +48,10 @@ The implementation of the physics plugin revolves around four key elements. FeatureLists can be constructed in hierarchies, e.g. a `FeatureList` can be passed into another `FeatureList`, and the set of all features in the new list will be the sum. -### FeatureList Definitions +## FeatureList Organization -This list of `FeatureLists` is specific to the implementation of `Dartsim` and `TPE-plugin`. -Users do not need to organize their own plugin implementations this way. +For example, here are the `FeatureLists` used in the implementation of the `Dartsim` physics engine. +Plugin implementations for other engines may choose to organize features into `FeatureLists` differently. | Name | Definition | |---|---| @@ -71,10 +67,7 @@ Users do not need to organize their own plugin implementations this way. | SimulationFeatures | updates `World` and everything within by defined stepsize | | WorldFeatures | sets options like solver and collision detector | -### Dart vs. TPE - - - +## Available Physics Plugins Dart ([Dynamic Animation and Robotics Toolkit](https://dartsim.github.io/)) is an open source library that provides data structures and algorithms for kinematic and dynamic applications in robotics and computer animation. It is the default physics engine used in Gazebo Simulation. @@ -82,12 +75,14 @@ The source code for Dartsim plugin can be found in [Gazebo Physics repository](h TPE ([Trivial Physics Engine](https://github.com/gazebosim/gz-physics/tree/main/tpe)) is an open source library created by Open Robotics that enables fast, inexpensive kinematics simulation for entities at large scale. It supports higher-order fleet dynamics without real physics (eg. gravity, force, constraint etc.) and multi-machine synchronization. -Gazebo support for TPE targets [Citadel](https://gazebosim.org/docs/citadel) and onward releases. The source code for TPE plugin can be found in [Gazebo Physics repository](https://github.com/gazebosim/gz-physics/tree/main) under the `tpe/plugin` directory. -The following is a list of features supported by each physics engine to help users select one that fits their needs. +Bullet ([Bullet3 Physics Engine](https://github.com/bulletphysics/bullet3)) is an open source library that supports real-time collision detection and multi-physics simulation for robotics and other application domains. +Since Bullet supports two different APIs - a rigid-body API and a multibody API - with different physics implementations, there are two available plugin implementations: +- The `bullet` plugin implements the rigid-body API, and the source code can be found in [Gazebo Physics repository](https://github.com/gazebosim/gz-physics/tree/main) under the `bullet` directory. +- The `bullet-featherstone` plugin implements the multibody API (based on Featherstone's algorithms), and the source code can be found in [Gazebo Physics repository](https://github.com/gazebosim/gz-physics/tree/main) under the `bullet-featherstone` directory. -#### Entity Comparison +### Entity Comparison The following is a table of `Entity` names used in Gazebo Physics plugin interface, Dart and TPE. Entities are arranged in top-down hierarchical order. @@ -103,60 +98,9 @@ Entities are arranged in top-down hierarchical order. | Shape | Shape | Collision | | Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder/Mesh etc. | -#### Feature Comparison +### Feature Comparison -The following is a table of implemented `Features` of Dartsim and TPE-Plugin. +For a list of all available `Features` in the Gazebo Physics library, check the classes inherited from `Feature` in the [Gazebo Physics API](https://gazebosim.org/api/physics/8/hierarchy.html). +To check if a physics plugin implements a particular `Feature`, check the `FeatureLists` supported by that plugin as specified in the plugin.cc file, for example, [dartsim/src/plugin.cc](https://github.com/gazebosim/gz-physics/blob/main/dartsim/src/plugin.cc). -| Features | Dartsim | TPE-Plugin | -|:-:|:-:|:-:| -| GetEntities | ✓ | ✓ (no joint in TPE) | -| RemoveEntities | ✓ | ✓ | -| ConstructEmptyWorldFeature | ✓ | ✓ | -| ConstructEmptyModelFeature | ✓ | ✓ | -| ConstructEmptyLinkFeature | ✓ | ✓ | -| CollisionFilterMaskFeature | ✓ | ✕ | -| FindFreeGroupFeature | ✓ | ✓ | -| SetFreeGroupWorldPose | ✓ | ✓ | -| SetFreeGroupWorldVelocity | ✓ | ✓ | -| GetBasicJointState | ✓ | ✕ | -| SetBasicJointState | ✓ | ✕ | -| GetBasicJointProperties | ✓ | ✕ | -| SetJointTransformFromParentFeature | ✓ | ✕ | -| SetJointTransformToChildFeature |✓ | ✕ | -| DetachJointFeature | ✓ | ✕ | -| SetFreeJointRelativeTransformFeature | ✓ | ✕ | -| AttachFixedJointFeature | ✓ | ✕ | -| SetRevoluteJointProperties | ✓ | ✕ | -| GetRevoluteJointProperties | ✓ | ✕ | -| AttachRevoluteJointFeature | ✓ | ✕ | -| SetPrismaticJointProperties | ✓ | ✕ | -| GetPrismaticJointProperties | ✓ | ✕ | -| AttachPrismaticJointFeature | ✓ | ✕ | -| SetJointVelocityCommandFeature | ✓ | ✕ | -| LinkFrameSemantics | ✓ | ✕ | -| ShapeFrameSemantics | ✓ | ✓ | -| FreeGroupFrameSemantics | ✓ | ✕ | -| AddLinkExternalForceTorque | ✓ | ✕ | -| sdf::ConstructSdfWorld | ✓ | ✓ | -| sdf::ConstructSdfModel | ✓ | ✓ | -| sdf::ConstructSdfLink | ✓ | ✓ | -| sdf::ConstructSdfJoint | ✓ | ✕ | -| sdf::ConstructSdfCollision | ✓ | ✕ | -| sdf::ConstructSdfVisual | ✓ | ✓ | -| GetShapeKinematicProperties | ✓ | ✓ | -| SetShapeKinematicProperties | ✓ | ✕ | -| GetShapeBoundingBox | ✓ | ✓ | -| GetBoxShapeProperties | ✓ | ✓ | -| AttachBoxShapeFeature | ✓ | ✓ | -| GetCylinderShapeProperties | ✓ | ✓ | -| AttachCylinderShapeFeature | ✓ | ✓ | -| GetSphereShapeProperties | ✓ | ✓ | -| AttachSphereShapeFeature | ✓ | ✓ | -| mesh::GetMeshShapeProperties | ✓ | ✓ | -| mesh::AttachMeshShapeFeature | ✓ | ✓ | -| ForwardStep | ✓ | ✓ | -| GetContactsFromLastStepFeature | ✓ | ✕ | -| CollisionDetector | ✓ | -| Solver | ✓ | -| heightmap::GetHeightmapShapeProperties | ✓ | | -| heightmap::AttachHeightmapShapeFeature | ✓ | | +Next, check out the tutorial on \ref pluginloading "Loading physics plugins" on how to access a specific `Feature` interface for a plugin programatically. From 6f55251ffe630cb757a28ffa3c99cccada79a791 Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Sat, 14 Sep 2024 02:07:48 -0700 Subject: [PATCH 3/8] Update entity mappings for bullet Signed-off-by: Shameek Ganguly --- tutorials/03_physics_plugins.md | 28 ++++++++++++++++------------ 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/tutorials/03_physics_plugins.md b/tutorials/03_physics_plugins.md index b382341a4..d1b414f3f 100644 --- a/tutorials/03_physics_plugins.md +++ b/tutorials/03_physics_plugins.md @@ -84,23 +84,27 @@ Since Bullet supports two different APIs - a rigid-body API and a multibody API ### Entity Comparison -The following is a table of `Entity` names used in Gazebo Physics plugin interface, Dart and TPE. +The following is a table of `Entity` names used in the Gazebo Physics plugin interface, mapped to corresonding types in each supported physics engine. Entities are arranged in top-down hierarchical order. -| Physics Plugin | Dart | TPE | -|:-:|:-:|:-:| -| Engine | Engine | Engine | -| World | World | World | -| Frame | Frame | N/A | -| Model | Skeleton | Model | -| Joint | Joint | N/A | -| Link | BodyNode | Link | -| Shape | Shape | Collision | -| Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder/Mesh etc. | +| Physics Plugin | Dart | TPE | Bullet | Bullet Featherstone | +|:-:|:-:|:-:|:-:| +| Engine | Engine | Engine | Engine | Engine | +| World | World | World | btDiscreteDynamicsWorld | btMultiBodyDynamicsWorld | +| Frame | Frame | N/A | N/A^* | N/A^* | +| Model | Skeleton | Model | N/A^# | btMultiBody | +| Joint | Joint | N/A | btTypedConstraint | btMultiBodyJoint^+ | +| Link | BodyNode | Link | btRigidBody | btMultiBodyLink | +| Shape | Shape | Collision | btCollisionShape | btCollisionShape | +| Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder etc. | + +^* Frames are implicitly attached to joints, links, collisions or models in the Bullet physics engine. +^# The Bullet rigid-body API does not have a concept of a Model, but the plugin maintains a collection of Links and Joints in the engine associated with a Model. +^+ There are multiple types in the Bullet Featherstone API to interact with joints, such as btMultiBodyJointLimitConstraint, btMultiBodyJointMotor and btMultiBodyJointFeedback. ### Feature Comparison For a list of all available `Features` in the Gazebo Physics library, check the classes inherited from `Feature` in the [Gazebo Physics API](https://gazebosim.org/api/physics/8/hierarchy.html). To check if a physics plugin implements a particular `Feature`, check the `FeatureLists` supported by that plugin as specified in the plugin.cc file, for example, [dartsim/src/plugin.cc](https://github.com/gazebosim/gz-physics/blob/main/dartsim/src/plugin.cc). -Next, check out the tutorial on \ref pluginloading "Loading physics plugins" on how to access a specific `Feature` interface for a plugin programatically. +Next, check out the tutorial on \ref pluginloading "Loading physics plugins" on how to load a plugin and access a specific `Feature` interface of the plugin programatically. From 693a2d8ba06a0c88005e869a784e47d03b72e3ed Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Sat, 14 Sep 2024 02:17:21 -0700 Subject: [PATCH 4/8] Fix entity table Signed-off-by: Shameek Ganguly --- tutorials/03_physics_plugins.md | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/tutorials/03_physics_plugins.md b/tutorials/03_physics_plugins.md index d1b414f3f..935290731 100644 --- a/tutorials/03_physics_plugins.md +++ b/tutorials/03_physics_plugins.md @@ -88,19 +88,21 @@ The following is a table of `Entity` names used in the Gazebo Physics plugin int Entities are arranged in top-down hierarchical order. | Physics Plugin | Dart | TPE | Bullet | Bullet Featherstone | -|:-:|:-:|:-:|:-:| +|:-:|:-:|:-:|:-:|:-:| | Engine | Engine | Engine | Engine | Engine | | World | World | World | btDiscreteDynamicsWorld | btMultiBodyDynamicsWorld | -| Frame | Frame | N/A | N/A^* | N/A^* | -| Model | Skeleton | Model | N/A^# | btMultiBody | -| Joint | Joint | N/A | btTypedConstraint | btMultiBodyJoint^+ | +| Frame | Frame | N/A | N/A1 | N/A1 | +| Model | Skeleton | Model | N/A2 | btMultiBody | +| Joint | Joint | N/A | btTypedConstraint | btMultiBodyJoint3 | | Link | BodyNode | Link | btRigidBody | btMultiBodyLink | | Shape | Shape | Collision | btCollisionShape | btCollisionShape | | Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder etc. | Box/Sphere/Cylinder etc. | -^* Frames are implicitly attached to joints, links, collisions or models in the Bullet physics engine. -^# The Bullet rigid-body API does not have a concept of a Model, but the plugin maintains a collection of Links and Joints in the engine associated with a Model. -^+ There are multiple types in the Bullet Featherstone API to interact with joints, such as btMultiBodyJointLimitConstraint, btMultiBodyJointMotor and btMultiBodyJointFeedback. +1 Frames are implicitly attached to joints, links, collisions or models in the Bullet physics engine. + +2 The Bullet rigid-body API does not have a concept of a Model, but the plugin maintains a collection of Links and Joints in the engine associated with a Model. + +3 There are multiple types in the Bullet Featherstone API to interact with joints, such as btMultiBodyJointLimitConstraint, btMultiBodyJointMotor and btMultiBodyJointFeedback. ### Feature Comparison @@ -108,3 +110,4 @@ For a list of all available `Features` in the Gazebo Physics library, check the To check if a physics plugin implements a particular `Feature`, check the `FeatureLists` supported by that plugin as specified in the plugin.cc file, for example, [dartsim/src/plugin.cc](https://github.com/gazebosim/gz-physics/blob/main/dartsim/src/plugin.cc). Next, check out the tutorial on \ref pluginloading "Loading physics plugins" on how to load a plugin and access a specific `Feature` interface of the plugin programatically. +e \ No newline at end of file From 8b5eef7b5e4dec45b23a5602df27b8fd44aed753 Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Sat, 14 Sep 2024 02:22:19 -0700 Subject: [PATCH 5/8] Fix typo Signed-off-by: Shameek Ganguly --- tutorials/03_physics_plugins.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tutorials/03_physics_plugins.md b/tutorials/03_physics_plugins.md index 935290731..17f209e2a 100644 --- a/tutorials/03_physics_plugins.md +++ b/tutorials/03_physics_plugins.md @@ -34,7 +34,7 @@ The implementation of the physics plugin revolves around four key elements. FeaturePolicy is a "policy class" used to provide metadata to features about what kind of simulation engine they are going to be used in. Many physics simulations software libraries model 3-dimensional systems, though some (like Box2d) only consider 2-dimensional systems. A FeaturePolicy is used to customize Gazebo Physics' APIs by the number of dimensions (2 or 3) and also the floating point scalar type (float or double). - (All of the currently supported physics engine use FeaturePolicy3d i.e. 3 dimensions and double.) + (All of the currently supported physics engines use FeaturePolicy3d i.e. 3 dimensions and double.) 3. \ref gz::physics::Feature "Feature" From 281f325f01f6dee6900827edc3f4783bc7fa14e6 Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Sat, 14 Sep 2024 02:23:20 -0700 Subject: [PATCH 6/8] Fix typo 2 Signed-off-by: Shameek Ganguly --- tutorials/03_physics_plugins.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tutorials/03_physics_plugins.md b/tutorials/03_physics_plugins.md index 17f209e2a..f94f6aa46 100644 --- a/tutorials/03_physics_plugins.md +++ b/tutorials/03_physics_plugins.md @@ -84,7 +84,7 @@ Since Bullet supports two different APIs - a rigid-body API and a multibody API ### Entity Comparison -The following is a table of `Entity` names used in the Gazebo Physics plugin interface, mapped to corresonding types in each supported physics engine. +The following is a table of `Entity` names used in the Gazebo Physics plugin interface, mapped to corresponding types in each supported physics engine. Entities are arranged in top-down hierarchical order. | Physics Plugin | Dart | TPE | Bullet | Bullet Featherstone | From 66992c26839c7c23a9d6019a7669187821fe653b Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Sat, 14 Sep 2024 02:24:20 -0700 Subject: [PATCH 7/8] Fix typo 3 Signed-off-by: Shameek Ganguly --- tutorials/03_physics_plugins.md | 1 - 1 file changed, 1 deletion(-) diff --git a/tutorials/03_physics_plugins.md b/tutorials/03_physics_plugins.md index f94f6aa46..444cf15f2 100644 --- a/tutorials/03_physics_plugins.md +++ b/tutorials/03_physics_plugins.md @@ -110,4 +110,3 @@ For a list of all available `Features` in the Gazebo Physics library, check the To check if a physics plugin implements a particular `Feature`, check the `FeatureLists` supported by that plugin as specified in the plugin.cc file, for example, [dartsim/src/plugin.cc](https://github.com/gazebosim/gz-physics/blob/main/dartsim/src/plugin.cc). Next, check out the tutorial on \ref pluginloading "Loading physics plugins" on how to load a plugin and access a specific `Feature` interface of the plugin programatically. -e \ No newline at end of file From f1dd3fc0da8634601749cc7b93a8e76108ca288b Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Sat, 14 Sep 2024 02:24:44 -0700 Subject: [PATCH 8/8] Fix typo 4 Signed-off-by: Shameek Ganguly --- tutorials/03_physics_plugins.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tutorials/03_physics_plugins.md b/tutorials/03_physics_plugins.md index 444cf15f2..2ea6e460c 100644 --- a/tutorials/03_physics_plugins.md +++ b/tutorials/03_physics_plugins.md @@ -109,4 +109,4 @@ Entities are arranged in top-down hierarchical order. For a list of all available `Features` in the Gazebo Physics library, check the classes inherited from `Feature` in the [Gazebo Physics API](https://gazebosim.org/api/physics/8/hierarchy.html). To check if a physics plugin implements a particular `Feature`, check the `FeatureLists` supported by that plugin as specified in the plugin.cc file, for example, [dartsim/src/plugin.cc](https://github.com/gazebosim/gz-physics/blob/main/dartsim/src/plugin.cc). -Next, check out the tutorial on \ref pluginloading "Loading physics plugins" on how to load a plugin and access a specific `Feature` interface of the plugin programatically. +Next, check out the tutorial on \ref pluginloading "Loading physics plugins" on how to load a plugin and access a specific `Feature` interface of the plugin programmatically.