#include <CameraPostProcessingRequestBus.h>
Inherits AZ::EBusSharedDispatchTraits< CameraPostProcessingRequests >.
|
using | BusIdType = AZ::EntityId |
| Each camera sensor component has its own post-processing bus.
|
|
|
static constexpr AZ::EBusAddressPolicy | AddressPolicy = AZ::EBusAddressPolicy::ById |
|
static constexpr AZ::EBusHandlerPolicy | HandlerPolicy = AZ::EBusHandlerPolicy::MultipleAndOrdered |
|
static constexpr AZ::u8 | MIN_PRIORITY = 0 |
|
static constexpr AZ::u8 | MAX_PRIORITY = 255 |
|
static constexpr AZ::u8 | DEFAULT_PRIORITY = 127 |
|
Interface class that allows to add post-processing to the pipeline
Each function call can be processed without blocking Bus for other dispatches. Do not use connects / disconnects to this bus during event dispatch, as they are not allowed for this concurrency model. Those constraints allow for processing multiple camera frames in the same time. Bus implementations should allow for asynchronous execution of provided functions.
◆ ApplyPostProcessing()
virtual void ROS2::CameraPostProcessingRequests::ApplyPostProcessing |
( |
sensor_msgs::msg::Image & |
image | ) |
|
|
pure virtual |
Apply post-processing function, if any implementations to the bus are in the entity.
- Parameters
-
image | standard image message passed as a reference. It will be changed through post-processing. |
- Note
- Handler should always handle function call, if handler does not support the format of the image, it should not change the image.
-
Every image is modified in place. Only one handler has access to the image at the time.
◆ Compare()
Compare function required by BusHandlerOrderCompare = BusHandlerCompareDefault
- Parameters
-
[in] | other | Another instance of the class to compare |
- Returns
- True if this bus should be processed before the other.
◆ GetPriority()
virtual AZ::u8 ROS2::CameraPostProcessingRequests::GetPriority |
( |
| ) |
const |
|
pure virtual |
Get priority of the post-processing bus.
- Returns
- priority of the bus.
- Note
- higher priority buses will be processed first.
◆ HandlerPolicy
constexpr AZ::EBusHandlerPolicy ROS2::CameraPostProcessingRequests::HandlerPolicy = AZ::EBusHandlerPolicy::MultipleAndOrdered |
|
staticconstexpr |
Multiple post-processing functions can be registered to the bus. They will be executed in the order
◆ MIN_PRIORITY
constexpr AZ::u8 ROS2::CameraPostProcessingRequests::MIN_PRIORITY = 0 |
|
staticconstexpr |
Priority of the post-processing bus.
- Note
- higher priority buses will be processed first.
The documentation for this class was generated from the following file:
- Gems/ROS2/Code/Include/ROS2/Camera/CameraPostProcessingRequestBus.h