#include <EntityFeatureMap.hh>
Public Types | |
template<typename T > | |
using | HasFeatureList = std::disjunction< std::is_same< T, OptionalFeatureLists >... > |
Checks whether type T is in the OptionalFeatureLists. More... | |
template<typename T > | |
using | PhysicsEntityPtr = physics::EntityPtr< PhysicsEntityT< PolicyT, T > > |
Template that's preset with the class's Policy type. More... | |
using | RequiredEntityPtr = PhysicsEntityPtr< RequiredFeatureList > |
A EntityPtr with made from RequiredFeatureList. More... | |
Public Member Functions | |
void | AddEntity (const Entity &_entity, const RequiredEntityPtr &_physicsEntity) |
Add a mapping between gazebo and physics entities. More... | |
template<typename ToFeatureList > | |
PhysicsEntityPtr< ToFeatureList > | EntityCast (const RequiredEntityPtr &_physicsEntity) const |
Helper function to cast from an entity type with minimum features to an entity with a different set of features. This overload takes a physics entity as input. More... | |
template<typename ToFeatureList > | |
PhysicsEntityPtr< ToFeatureList > | EntityCast (gz::sim::Entity _entity) const |
Helper function to cast from an entity type with minimum features to an entity with a different set of features. When the entity is cast successfully, it is added to an internal cache so that subsequent casts will use the entity from the cache. More... | |
RequiredEntityPtr | Get (const Entity &_entity) const |
Get the physics entity with required features that corresponds to the input Gazebo entity. More... | |
Entity | Get (const RequiredEntityPtr &_physEntity) const |
Get Gazebo entity that corresponds to the physics entity with required features. More... | |
Entity | GetByPhysicsId (std::size_t _id) const |
Get Gazebo entity that corresponds to the physics entity ID. More... | |
RequiredEntityPtr | GetPhysicsEntityPtr (std::size_t _id) const |
Get the physics entity with required features that has a particular ID. More... | |
bool | HasEntity (const Entity &_entity) const |
Check whether there is a physics entity associated with the given Gazebo entity. More... | |
bool | HasEntity (const RequiredEntityPtr &_physicsEntity) const |
Check whether there is a gazebo entity associated with the given physics entity. More... | |
const std::unordered_map< Entity, RequiredEntityPtr > & | Map () const |
Get the map from Gazebo entity to physics entities with required features. More... | |
bool | Remove (const RequiredEntityPtr &_physicsEntity) |
Remove physics entity from all associated maps. More... | |
bool | Remove (Entity _entity) |
Remove entity from all associated maps. More... | |
std::size_t | TotalMapEntryCount () const |
Get the total number of entries in the maps. Only used for testing. More... | |
Member Typedef Documentation
◆ HasFeatureList
using HasFeatureList = std::disjunction<std::is_same<T, OptionalFeatureLists>...> |
Checks whether type T is in the OptionalFeatureLists.
- Template Parameters
-
T A FeatureList to search for in OptionalFeatureLists
◆ PhysicsEntityPtr
using PhysicsEntityPtr = physics::EntityPtr<PhysicsEntityT<PolicyT, T> > |
Template that's preset with the class's Policy type.
- Template Parameters
-
T A FeatureList that is used in creating an EntityPtr
◆ RequiredEntityPtr
using RequiredEntityPtr = PhysicsEntityPtr<RequiredFeatureList> |
A EntityPtr with made from RequiredFeatureList.
Member Function Documentation
◆ AddEntity()
|
inline |
Add a mapping between gazebo and physics entities.
- Parameters
-
[in] _entity Gazebo entity. [in] _physicsEntity Physics entity with required feature
◆ EntityCast() [1/2]
|
inline |
Helper function to cast from an entity type with minimum features to an entity with a different set of features. This overload takes a physics entity as input.
- Template Parameters
-
ToFeatureList The list of features of the resulting entity.
- Parameters
-
[in] _physicsEntity Physics entity with required features.
- Returns
- Physics entity with features in ToFeatureList. nullptr if the entity can't be found or the physics engine doesn't support the requested feature.
References EntityFeatureMap< PhysicsEntityT, PolicyT, RequiredFeatureList, OptionalFeatureLists >::Get(), and ignition::gazebo::kNullEntity.
◆ EntityCast() [2/2]
|
inline |
Helper function to cast from an entity type with minimum features to an entity with a different set of features. When the entity is cast successfully, it is added to an internal cache so that subsequent casts will use the entity from the cache.
- Template Parameters
-
ToFeatureList The list of features of the resulting entity.
- Parameters
-
[in] _entity Gazebo entity.
- Returns
- Physics entity with features in ToFeatureList. nullptr if the entity can't be found or the physics engine doesn't support the requested feature.
References EntityFeatureMap< PhysicsEntityT, PolicyT, RequiredFeatureList, OptionalFeatureLists >::Get().
◆ Get() [1/2]
|
inline |
Get the physics entity with required features that corresponds to the input Gazebo entity.
- Parameters
-
[in] _entity Gazebo entity.
- Returns
- If found, returns the corresponding physics entity. Otherwise, nullptr
References unordered_map< K, T >::end(), and unordered_map< K, T >::find().
Referenced by EntityFeatureMap< PhysicsEntityT, PolicyT, RequiredFeatureList, OptionalFeatureLists >::EntityCast().
◆ Get() [2/2]
|
inline |
Get Gazebo entity that corresponds to the physics entity with required features.
- Parameters
-
[in] _physEntity Physics entity with required features
- Returns
- If found, returns the corresponding Gazebo entity. Otherwise, kNullEntity
References unordered_map< K, T >::end(), unordered_map< K, T >::find(), and ignition::gazebo::kNullEntity.
◆ GetByPhysicsId()
|
inline |
Get Gazebo entity that corresponds to the physics entity ID.
- Parameters
-
[in] _id Physics entity ID
- Returns
- If found, returns the corresponding Gazebo entity. Otherwise, kNullEntity
References unordered_map< K, T >::end(), unordered_map< K, T >::find(), and ignition::gazebo::kNullEntity.
◆ GetPhysicsEntityPtr()
|
inline |
Get the physics entity with required features that has a particular ID.
- Parameters
-
[in] _id The ID of the desired physics entity
- Returns
- If found, returns the corresponding physics entity. Otherwise, nullptr
References unordered_map< K, T >::end(), and unordered_map< K, T >::find().
◆ HasEntity() [1/2]
|
inline |
Check whether there is a physics entity associated with the given Gazebo entity.
- Parameters
-
[in] _entity Gazebo entity.
- Returns
- True if the there is a physics entity associated with the given Gazebo entity
References unordered_map< K, T >::end(), and unordered_map< K, T >::find().
◆ HasEntity() [2/2]
|
inline |
Check whether there is a gazebo entity associated with the given physics entity.
- Parameters
-
[in] _physicsEntity physics entity with required features.
- Returns
- True if the there is a gazebo entity associated with the given physics entity
References unordered_map< K, T >::end(), and unordered_map< K, T >::find().
◆ Map()
|
inline |
Get the map from Gazebo entity to physics entities with required features.
- Returns
- Immumtable entity map
◆ Remove() [1/2]
|
inline |
Remove physics entity from all associated maps.
- Parameters
-
[in] _physicsEntity Physics entity.
- Returns
- True if the entity was found and removed.
References unordered_map< K, T >::end(), unordered_map< K, T >::erase(), and unordered_map< K, T >::find().
◆ Remove() [2/2]
|
inline |
Remove entity from all associated maps.
- Parameters
-
[in] _entity Gazebo entity.
- Returns
- True if the entity was found and removed.
References unordered_map< K, T >::end(), unordered_map< K, T >::erase(), and unordered_map< K, T >::find().
◆ TotalMapEntryCount()
|
inline |
Get the total number of entries in the maps. Only used for testing.
- Returns
- Number of entries in all the maps.
References unordered_map< K, T >::size().
The documentation for this class was generated from the following file: