#include <CameraSensor.h>
Inherited by ROS2::CameraColorSensor, and ROS2::CameraDepthSensor.
|
void | RequestFrame (const AZ::Transform &cameraPose, AZStd::function< void(const AZ::RPI::AttachmentReadback::ReadbackResult &result)> callback) |
|
void | SetupPasses () |
| Read and setup Atom Passes.
|
|
Class to create camera sensor using Atom renderer It creates dedicated rendering pipeline for each camera
◆ CameraSensor()
ROS2::CameraSensor::CameraSensor |
( |
const CameraSensorDescription & |
cameraSensorDescription, |
|
|
const AZ::EntityId & |
entityId |
|
) |
| |
Initializes rendering pipeline for the camera sensor.
- Parameters
-
cameraSensorDescription | - camera sensor description used to create camera pipeline. |
entityId | - entityId for the owning sensor component. |
◆ RequestFrame()
void ROS2::CameraSensor::RequestFrame |
( |
const AZ::Transform & |
cameraPose, |
|
|
AZStd::function< void(const AZ::RPI::AttachmentReadback::ReadbackResult &result)> |
callback |
|
) |
| |
|
protected |
Request a frame from the rendering pipeline
- Parameters
-
cameraPose | - current camera pose from which the rendering should take place |
callback | - callback function object that will be called when capture is ready. It's argument is readback structure containing, among other things, a captured image |
◆ RequestMessagePublication()
virtual void ROS2::CameraSensor::RequestMessagePublication |
( |
const AZ::Transform & |
cameraPose, |
|
|
const std_msgs::msg::Header & |
header |
|
) |
| |
|
virtual |
Publish Image Message frame from rendering pipeline
- Parameters
-
cameraPose | - current camera pose from which the rendering should take place |
header | - header with filled message information (frame, timestamp, seq) |
Reimplemented in ROS2::CameraRGBDSensor.
The documentation for this class was generated from the following file:
- Gems/ROS2/Code/Source/Camera/CameraSensor.h