All component instances of the same type are stored squentially in memory. This is a base class for storing components of a particular type. More...
#include <ComponentStorageBase.hh>
Public Member Functions | |
ComponentStorageBase ()=default | |
Constructor. More... | |
virtual | ~ComponentStorageBase ()=default |
Destructor. More... | |
virtual const components::BaseComponent * | Component (const ComponentId _id) const =0 |
Get a component based on an id. More... | |
virtual components::BaseComponent * | Component (const ComponentId _id)=0 |
Get a mutable component based on an id. More... | |
virtual std::pair< ComponentId, bool > | Create (const components::BaseComponent *_data)=0 |
Create a new component using the provided data. More... | |
virtual components::BaseComponent * | First ()=0 |
Get the first component. More... | |
virtual bool | Remove (const ComponentId _id)=0 |
Remove a component based on an id. More... | |
virtual void | RemoveAll ()=0 |
Remove all components. More... | |
Protected Attributes | |
std::mutex | mutex |
Mutex used to prevent data corruption. More... | |
Detailed Description
All component instances of the same type are stored squentially in memory. This is a base class for storing components of a particular type.
Constructor & Destructor Documentation
◆ ComponentStorageBase()
|
default |
Constructor.
◆ ~ComponentStorageBase()
|
virtualdefault |
Destructor.
Member Function Documentation
◆ Component() [1/2]
|
pure virtual |
Get a component based on an id.
- Parameters
-
[in] _id Id of the component to get.
- Returns
- A pointer to the component, or nullptr if the component could not be found.
Implemented in ComponentStorage< ComponentTypeT >.
◆ Component() [2/2]
|
pure virtual |
Get a mutable component based on an id.
- Parameters
-
[in] _id Id of the component to get.
- Returns
- A pointer to the component, or nullptr if the component could not be found.
Implemented in ComponentStorage< ComponentTypeT >.
◆ Create()
|
pure virtual |
Create a new component using the provided data.
- Parameters
-
[in] _data Data used to construct the component.
- Returns
- Id of the new component, and whether the components array was expanded. kComponentIdInvalid is returned if the component could not be created.
Implemented in ComponentStorage< ComponentTypeT >.
◆ First()
|
pure virtual |
Get the first component.
- Returns
- First component or nullptr if there are no components.
Implemented in ComponentStorage< ComponentTypeT >.
◆ Remove()
|
pure virtual |
Remove a component based on an id.
- Parameters
-
[in] _id Id of the component to remove.
- Returns
- True if the component was removed.
Implemented in ComponentStorage< ComponentTypeT >.
◆ RemoveAll()
|
pure virtual |
Remove all components.
Implemented in ComponentStorage< ComponentTypeT >.
Member Data Documentation
◆ mutex
|
mutableprotected |
Mutex used to prevent data corruption.
The documentation for this class was generated from the following file: