Skip to content

Commit

Permalink
Adjusted to review
Browse files Browse the repository at this point in the history
Signed-off-by: Michał Pełka <[email protected]>
  • Loading branch information
michalpelka committed Mar 13, 2023
1 parent 3000953 commit c787906
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 10 deletions.
12 changes: 6 additions & 6 deletions Gems/ROS2/Code/Source/Camera/CameraSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,9 +117,8 @@ namespace ROS2
m_view->SetViewToClipMatrix(m_cameraSensorDescription.m_viewToClipMatrix);
m_scene = AZ::RPI::RPISystemInterface::Get()->GetSceneByName(AZ::Name("Main"));

m_pipelineName = m_cameraSensorDescription.m_cameraName + "Pipeline" + GetPipelineTypeName() +
m_cameraSensorDescription.m_entityId.ToString();

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 = m_pipelineName;
Expand Down Expand Up @@ -218,11 +217,12 @@ namespace ROS2
}

void CameraSensor::RequestMessagePublication(
AZStd::vector<std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>>> publishers,
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()){
if (!publishers.empty())
{
RequestMessagePublication(publishers.front(), cameraPose, header);
}
}
Expand Down Expand Up @@ -279,7 +279,7 @@ namespace ROS2
}

void CameraRGBDSensor::RequestMessagePublication(
AZStd::vector<std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>>> publishers,
AZStd::span<std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>>> publishers,
const AZ::Transform& cameraPose,
const std_msgs::msg::Header& header)
{
Expand Down
5 changes: 3 additions & 2 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 Down Expand Up @@ -62,7 +63,7 @@ namespace ROS2
//! @param header - header with filled message information (frame, timestamp, seq)
//! @param cameraPose - current camera pose from which the rendering should take place
virtual void RequestMessagePublication(
AZStd::vector<std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>>> publishers,
AZStd::span<std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image>>> publishers,
const AZ::Transform& cameraPose,
const std_msgs::msg::Header& header);

Expand Down Expand Up @@ -144,7 +145,7 @@ namespace ROS2

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

Expand Down
1 change: 0 additions & 1 deletion Gems/ROS2/Code/Source/Camera/ROS2CameraSensorComponent.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,5 @@ namespace ROS2
return cameraName;
}
return AZStd::string{};

}
} // namespace ROS2
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ namespace ROS2
void Activate() override;
void Deactivate() override;

//! AzToolsFramework::Components::EditorComponentBase override
// AzToolsFramework::Components::EditorComponentBase override
void BuildGameEntity(AZ::Entity* gameEntity) override;

private:
Expand Down

0 comments on commit c787906

Please sign in to comment.