Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enable rendering pipeline modifiers in camera sensor #6

Draft
wants to merge 5 commits into
base: mp/rgbd_cameras
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
"ClassName": "PassAsset",
"ClassData": {
"PassTemplate": {
"Name": "PipelineRenderToTextureROSDepth",
"Name": "PipelineRenderToTextureROSColor",
"PassClass": "RenderToTexturePass",
"PassData": {
"$type": "RenderToTexturePassData",
Expand Down
97 changes: 81 additions & 16 deletions Gems/ROS2/Code/Source/Camera/CameraSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,14 +52,16 @@ namespace ROS2
};

} // namespace Internal
CameraSensorDescription::CameraSensorDescription(const AZStd::string& cameraName, float verticalFov, int width, int height)
CameraSensorDescription::CameraSensorDescription(const AZStd::string& cameraName, float verticalFov, int width, int height, AZ::EntityId entityId, bool renderPipelineAllowModification)
: m_verticalFieldOfViewDeg(verticalFov)
, m_width(width)
, m_height(height)
, m_cameraName(cameraName)
, m_aspectRatio(static_cast<float>(width) / static_cast<float>(height))
, m_viewToClipMatrix(MakeViewToClipMatrix())
, m_cameraIntrinsics(MakeCameraIntrinsics())
, m_entityId(entityId)
, m_renderPipelineAllowModification(renderPipelineAllowModification)
{
ValidateParameters();
}
Expand Down Expand Up @@ -116,15 +118,17 @@ namespace ROS2
m_view->SetViewToClipMatrix(m_cameraSensorDescription.m_viewToClipMatrix);
m_scene = AZ::RPI::RPISystemInterface::Get()->GetSceneByName(AZ::Name("Main"));

const AZStd::string pipelineName = m_cameraSensorDescription.m_cameraName + "Pipeline" + GetPipelineTypeName();

m_pipelineName = AZStd::string::format("%sPipeline%s%s",m_cameraSensorDescription.m_cameraName.c_str(), GetPipelineTypeName().c_str(),
m_cameraSensorDescription.m_entityId.ToString().c_str() );
AZ::RPI::RenderPipelineDescriptor pipelineDesc;
pipelineDesc.m_mainViewTagName = "MainCamera";
pipelineDesc.m_name = pipelineName;
pipelineDesc.m_name = m_pipelineName;

pipelineDesc.m_rootPassTemplate = GetPipelineTemplateName();

pipelineDesc.m_renderSettings.m_multisampleState = AZ::RPI::RPISystemInterface::Get()->GetApplicationMultisampleState();
pipelineDesc.m_allowModification = m_cameraSensorDescription.m_renderPipelineAllowModification;

m_pipeline = AZ::RPI::RenderPipeline::CreateRenderPipeline(pipelineDesc);
m_pipeline->RemoveFromRenderTick();

Expand All @@ -135,7 +139,7 @@ namespace ROS2

m_scene->AddRenderPipeline(m_pipeline);

m_passHierarchy.push_back(pipelineName);
m_passHierarchy.push_back(m_pipelineName);
m_passHierarchy.push_back("CopyToSwapChain");

m_pipeline->SetDefaultView(m_view);
Expand Down Expand Up @@ -198,20 +202,34 @@ namespace ROS2
cameraPose,
[header, publisher](const AZ::RPI::AttachmentReadback::ReadbackResult& result)
{
const AZ::RHI::ImageDescriptor& descriptor = result.m_imageDescriptor;
const auto format = descriptor.m_format;
AZ_Assert(Internal::FormatMappings.contains(format), "Unknown format in result %u", static_cast<uint32_t>(format));
sensor_msgs::msg::Image message;
message.encoding = Internal::FormatMappings.at(format);
message.width = descriptor.m_size.m_width;
message.height = descriptor.m_size.m_height;
message.step = message.width * Internal::BitDepth.at(format);
message.data = std::vector<uint8_t>(result.m_dataBuffer->data(), result.m_dataBuffer->data() + result.m_dataBuffer->size());
message.header = header;
publisher->publish(message);
if (result.m_state == AZ::RPI::AttachmentReadback::ReadbackState::Success)
{
const AZ::RHI::ImageDescriptor& descriptor = result.m_imageDescriptor;
const auto format = descriptor.m_format;
AZ_Assert(Internal::FormatMappings.contains(format), "Unknown format in result %u", static_cast<uint32_t>(format));
sensor_msgs::msg::Image message;
message.encoding = Internal::FormatMappings.at(format);
message.width = descriptor.m_size.m_width;
message.height = descriptor.m_size.m_height;
message.step = message.width * Internal::BitDepth.at(format);
message.data = std::vector<uint8_t>(result.m_dataBuffer->data(), result.m_dataBuffer->data() + result.m_dataBuffer->size());
message.header = header;
publisher->publish(message);
}
});
}

void CameraSensor::RequestMessagePublication(
AZStd::span<std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>>> publishers,
const AZ::Transform& cameraPose,
const std_msgs::msg::Header& header)
{
if (!publishers.empty())
{
RequestMessagePublication(publishers.front(), cameraPose, header);
}
}

CameraDepthSensor::CameraDepthSensor(const CameraSensorDescription& cameraSensorDescription)
: CameraSensor(cameraSensorDescription)
{
Expand Down Expand Up @@ -244,4 +262,51 @@ namespace ROS2
return "Color";
};

CameraRGBDSensor::CameraRGBDSensor(const CameraSensorDescription& cameraSensorDescription)
: CameraColorSensor(cameraSensorDescription)
{
}

void CameraRGBDSensor::ReadBackDepth(
AZStd::function<void(const AZ::RPI::AttachmentReadback::ReadbackResult& result)> callback)
{
AZ::Render::FrameCaptureOutcome captureOutcome;
AZStd::vector<AZStd::string> passHierarchy{m_pipelineName,"DepthPrePass"};
AZ::Render::FrameCaptureRequestBus::BroadcastResult(
captureOutcome,
&AZ::Render::FrameCaptureRequestBus::Events::CapturePassAttachmentWithCallback,
callback,
passHierarchy,
AZStd::string("DepthLinear"),
AZ::RPI::PassAttachmentReadbackOption::Output);
}

void CameraRGBDSensor::RequestMessagePublication(
AZStd::span<std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>>> publishers,
const AZ::Transform& cameraPose,
const std_msgs::msg::Header& header)
{
AZ_Assert(publishers.size()==2, "RequestMessagePublication for CameraRGBDSensor should be called with exactly two publishers");
const auto publisherDepth = publishers.back();
ReadBackDepth(
[header, publisherDepth](const AZ::RPI::AttachmentReadback::ReadbackResult& result)
{
if (result.m_state == AZ::RPI::AttachmentReadback::ReadbackState::Success)
{
const AZ::RHI::ImageDescriptor& descriptor = result.m_imageDescriptor;
const auto format = descriptor.m_format;
AZ_Assert(Internal::FormatMappings.contains(format), "Unknown format in result %u", static_cast<uint32_t>(format));
sensor_msgs::msg::Image message;
message.encoding = Internal::FormatMappings.at(format);
message.width = descriptor.m_size.m_width;
message.height = descriptor.m_size.m_height;
message.step = message.width * Internal::BitDepth.at(format);
message.data = std::vector<uint8_t>(result.m_dataBuffer->data(), result.m_dataBuffer->data() + result.m_dataBuffer->size());
message.header = header;
publisherDepth->publish(message);
}
});
CameraSensor::RequestMessagePublication(publishers,cameraPose,header);
}

} // namespace ROS2
63 changes: 52 additions & 11 deletions Gems/ROS2/Code/Source/Camera/CameraSensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
#pragma once

#include <Atom/Feature/Utils/FrameCaptureBus.h>
#include <AzCore/std/containers/span.h>
#include <ROS2/ROS2GemUtilities.h>
#include <chrono>
#include <rclcpp/publisher.hpp>
Expand All @@ -25,17 +26,21 @@ namespace ROS2
//! @param verticalFov - vertical field of view of camera sensor
//! @param width - camera image width in pixels
//! @param height - camera image height in pixels
CameraSensorDescription(const AZStd::string& cameraName, float verticalFov, int width, int height);
//! @param entityId - entityId of camera sensor
//! @param renderPipelineAllowModification - allow render pipeline modification (required to enable postprocessing, GI, etc.)
CameraSensorDescription(const AZStd::string& cameraName, float verticalFov,
int width, int height, AZ::EntityId entityId, bool renderPipelineAllowModification);

const float m_verticalFieldOfViewDeg; //!< camera vertical field of view
const int m_width; //!< camera image width in pixels
const int m_height; //!< camera image height in pixels
const AZStd::string m_cameraName; //!< camera name to differentiate cameras in a multi-camera setup
const bool m_renderPipelineAllowModification; //!< allow render pipeline modification (required to enable postprocessing, GI, etc.)

const float m_aspectRatio; //!< camera image aspect ratio; equal to (width / height)
const AZ::Matrix4x4 m_viewToClipMatrix; //!< camera view to clip space transform matrix; derived from other parameters
const AZStd::array<double, 9> m_cameraIntrinsics; //!< camera intrinsics; derived from other parameters

const AZ::EntityId m_entityId; //! Entity Id that is owning this sensor.
private:
AZ::Matrix4x4 MakeViewToClipMatrix() const;

Expand All @@ -57,28 +62,29 @@ namespace ROS2
virtual ~CameraSensor();

//! Publish Image Message frame from rendering pipeline
//! @param publisher - ROS2 publisher to publish image in future
//! @param publishers - ROS2 publishers to publish image in future : color, depth ...
//! @param header - header with filled message information (frame, timestamp, seq)
//! @param cameraPose - current camera pose from which the rendering should take place
void RequestMessagePublication(
std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>> publisher,
virtual void RequestMessagePublication(
AZStd::span<std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>>> publishers,
const AZ::Transform& cameraPose,
const std_msgs::msg::Header& header);

//! Get the camera sensor description
[[nodiscard]] const CameraSensorDescription& GetCameraSensorDescription() const;

private:
//! Request a frame from the rendering pipeline
//! Publish Image Message frame from rendering pipeline
//! @param publisher - ROS2 publisher to publish image in future
//! @param header - header with filled message information (frame, timestamp, seq)
//! @param cameraPose - current camera pose from which the rendering should take place
//! @param callback - callback function object that will be called when capture is ready
//! it's argument is readback structure containing, among other thins, captured image
void RequestFrame(
const AZ::Transform& cameraPose, AZStd::function<void(const AZ::RPI::AttachmentReadback::ReadbackResult& result)> callback);
void RequestMessagePublication(
std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>> publisher,
const AZ::Transform& cameraPose,
const std_msgs::msg::Header& header);

CameraSensorDescription m_cameraSensorDescription;
AZStd::vector<AZStd::string> m_passHierarchy;
AZ::RPI::RenderPipelinePtr m_pipeline;
AZ::RPI::ViewPtr m_view;
AZ::RPI::Scene* m_scene = nullptr;
const AZ::Transform AtomToRos{ AZ::Transform::CreateFromQuaternion(
Expand All @@ -87,6 +93,26 @@ namespace ROS2
virtual AZStd::string GetPipelineTypeName() const = 0; //! Type of returned data eg Color, Depth, Optical flow

protected:
AZ::RPI::RenderPipelinePtr m_pipeline;
AZStd::string m_pipelineName;

//! Request a frame from the rendering pipeline
//! @param cameraPose - current camera pose from which the rendering should take place
//! @param 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
void RequestFrame(
const AZ::Transform& cameraPose, AZStd::function<void(const AZ::RPI::AttachmentReadback::ReadbackResult& result)> callback);

//! Request an additional frame from the rendering pipeline
//! @param 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
//! @param passName - pass name in pipeline, eg `DepthToLinearDepthPass`
//! @param slotName - slot name in selected pass, eg `Output`
void RequestAdditionalFrame(
AZStd::function<void(const AZ::RPI::AttachmentReadback::ReadbackResult& result)> callback,
const AZStd::string& passName,
const AZStd::string& slotName);

//! Read and setup Atom Passes
void SetupPasses();
};
Expand All @@ -113,4 +139,19 @@ namespace ROS2
AZStd::string GetPipelineTypeName() const override;
};

//! Implementation of camera sensors that runs pipeline which produces color image and readbacks a depth image from pipeline
class CameraRGBDSensor : public CameraColorSensor
{
public:
CameraRGBDSensor(const CameraSensorDescription& cameraSensorDescription);

// CameraSensor overrides
void RequestMessagePublication(
AZStd::span<std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>>> publishers,
const AZ::Transform& cameraPose,
const std_msgs::msg::Header& header) override;

private:
void ReadBackDepth(AZStd::function<void(const AZ::RPI::AttachmentReadback::ReadbackResult& result)> callback);
};
} // namespace ROS2
42 changes: 28 additions & 14 deletions Gems/ROS2/Code/Source/Camera/ROS2CameraSensorComponent.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,12 +27,14 @@ namespace ROS2
int width,
int height,
bool colorCamera,
bool depthCamera)
bool depthCamera,
bool renderPipelineAllowModification)
: m_verticalFieldOfViewDeg(verticalFieldOfViewDeg)
, m_width(width)
, m_height(height)
, m_colorCamera(colorCamera)
, m_depthCamera(depthCamera)
, m_renderPipelineAllowModification(renderPipelineAllowModification)
{
m_sensorConfiguration = sensorConfiguration;
}
Expand All @@ -48,7 +50,8 @@ namespace ROS2
->Field("Width", &ROS2CameraSensorComponent::m_width)
->Field("Height", &ROS2CameraSensorComponent::m_height)
->Field("Depth", &ROS2CameraSensorComponent::m_depthCamera)
->Field("Color", &ROS2CameraSensorComponent::m_colorCamera);
->Field("Color", &ROS2CameraSensorComponent::m_colorCamera)
->Field("AllowModification", &ROS2CameraSensorComponent::m_renderPipelineAllowModification);
}
}

Expand All @@ -66,32 +69,47 @@ namespace ROS2
ros2Node->create_publisher<sensor_msgs::msg::CameraInfo>(cameraInfoFullTopic.data(), cameraInfoPublisherConfig.GetQoS());

const CameraSensorDescription description{
GetCameraNameFromFrame(GetEntity()), m_verticalFieldOfViewDeg, m_width, m_height
GetCameraNameFromFrame(GetEntity()), m_verticalFieldOfViewDeg, m_width, m_height, GetEntityId(), m_renderPipelineAllowModification
};
if (m_colorCamera)
{
const auto cameraImagePublisherConfig = m_sensorConfiguration.m_publishersConfigurations[CameraConstants::ColorImageConfig];
AZStd::string cameraImageFullTopic = ROS2Names::GetNamespacedName(GetNamespace(), cameraImagePublisherConfig.m_topic);
auto publisher =
ros2Node->create_publisher<sensor_msgs::msg::Image>(cameraImageFullTopic.data(), cameraImagePublisherConfig.GetQoS());
m_cameraSensorsWithPublihsers.emplace_back(CreatePair<CameraColorSensor>(publisher, description));
m_imagePublishers.emplace_back(publisher);
}
if (m_depthCamera)
{
const auto cameraImagePublisherConfig = m_sensorConfiguration.m_publishersConfigurations[CameraConstants::DepthImageConfig];
AZStd::string cameraImageFullTopic = ROS2Names::GetNamespacedName(GetNamespace(), cameraImagePublisherConfig.m_topic);
auto publisher =
ros2Node->create_publisher<sensor_msgs::msg::Image>(cameraImageFullTopic.data(), cameraImagePublisherConfig.GetQoS());
m_cameraSensorsWithPublihsers.emplace_back(CreatePair<CameraDepthSensor>(publisher, description));
m_imagePublishers.emplace_back(publisher);
}

if (m_colorCamera && m_depthCamera)
{
m_cameraSensor = AZStd::make_shared<CameraRGBDSensor>(description);
}
else if (m_colorCamera)
{
m_cameraSensor = AZStd::make_shared<CameraColorSensor>(description);
}
else if (m_depthCamera)
{
m_cameraSensor = AZStd::make_shared<CameraDepthSensor>(description);
}

const auto* component = Utils::GetGameOrEditorComponent<ROS2FrameComponent>(GetEntity());
AZ_Assert(component, "Entity has no ROS2FrameComponent");
m_frameName = component->GetFrameID();
}

void ROS2CameraSensorComponent::Deactivate()
{
m_cameraSensorsWithPublihsers.clear();
m_cameraSensor.reset();
m_imagePublishers.clear();
ROS2SensorComponent::Deactivate();
}

Expand All @@ -100,10 +118,10 @@ namespace ROS2
const AZ::Transform transform = GetEntity()->GetTransform()->GetWorldTM();
const auto timestamp = ROS2Interface::Get()->GetROSTimestamp();
std_msgs::msg::Header ros_header;
if (!m_cameraSensorsWithPublihsers.empty())
if (!m_imagePublishers.empty() && m_cameraSensor)
{
const auto& camera_descritpion = m_cameraSensorsWithPublihsers.front().second->GetCameraSensorDescription();
const auto& cameraIntrinsics = camera_descritpion.m_cameraIntrinsics;
const auto& cameraDescription = m_cameraSensor->GetCameraSensorDescription();
const auto& cameraIntrinsics = cameraDescription.m_cameraIntrinsics;
sensor_msgs::msg::CameraInfo cameraInfo;
ros_header.stamp = timestamp;
ros_header.frame_id = m_frameName.c_str();
Expand All @@ -117,10 +135,7 @@ namespace ROS2
cameraInfo.p = { cameraInfo.k[0], cameraInfo.k[1], cameraInfo.k[2], 0, cameraInfo.k[3], cameraInfo.k[4], cameraInfo.k[5], 0,
cameraInfo.k[6], cameraInfo.k[7], cameraInfo.k[8], 0 };
m_cameraInfoPublisher->publish(cameraInfo);
}
for (auto& [publisher, sensor] : m_cameraSensorsWithPublihsers)
{
sensor->RequestMessagePublication(publisher, transform, ros_header);
m_cameraSensor->RequestMessagePublication(m_imagePublishers, transform, ros_header );
}
}

Expand All @@ -135,6 +150,5 @@ namespace ROS2
return cameraName;
}
return AZStd::string{};

}
} // namespace ROS2
Loading