Ver código fonte

Standards and styles : std usage, auto, nullptr, rtti (#329)

* reviewed usage of 'auto'
* Adjusted usage  of std and auto
* remove rtti and exceptions from ROS2.Static target

Signed-off-by: Michał Pełka <[email protected]>
Michał Pełka 2 anos atrás
pai
commit
54bb7ed406
35 arquivos alterados com 119 adições e 116 exclusões
  1. 3 7
      Gems/ROS2/Code/CMakeLists.txt
  2. 0 0
      Gems/ROS2/Code/Platform/Common/Clang/ros2_static_editor_clang.cmake
  3. 0 0
      Gems/ROS2/Code/Platform/Common/GCC/ros2_static_editor_gcc.cmake
  4. 0 0
      Gems/ROS2/Code/Platform/Common/msvc/ros2_static_editor_msvc.cmake
  5. 21 14
      Gems/ROS2/Code/Source/Camera/CameraSensor.cpp
  6. 1 2
      Gems/ROS2/Code/Source/Camera/ROS2CameraSensorComponent.cpp
  7. 1 1
      Gems/ROS2/Code/Source/Camera/ROS2CameraSensorComponent.h
  8. 1 1
      Gems/ROS2/Code/Source/Clock/SimulationClock.cpp
  9. 2 2
      Gems/ROS2/Code/Source/Frame/ROS2FrameComponent.cpp
  10. 5 5
      Gems/ROS2/Code/Source/GNSS/GNSSFormatConversions.cpp
  11. 1 1
      Gems/ROS2/Code/Source/Lidar/LidarRaycaster.cpp
  12. 1 1
      Gems/ROS2/Code/Source/Lidar/LidarRaycaster.h
  13. 1 1
      Gems/ROS2/Code/Source/Lidar/ROS2LidarSensorComponent.cpp
  14. 2 2
      Gems/ROS2/Code/Source/ROS2GemUtilities.cpp
  15. 1 1
      Gems/ROS2/Code/Source/RobotImporter/URDF/CollidersMaker.cpp
  16. 1 1
      Gems/ROS2/Code/Source/RobotImporter/URDF/CollidersMaker.h
  17. 1 1
      Gems/ROS2/Code/Source/RobotImporter/URDF/InertialsMaker.cpp
  18. 1 1
      Gems/ROS2/Code/Source/RobotImporter/URDF/InertialsMaker.h
  19. 1 1
      Gems/ROS2/Code/Source/RobotImporter/URDF/JointsMaker.cpp
  20. 1 1
      Gems/ROS2/Code/Source/RobotImporter/URDF/JointsMaker.h
  21. 1 1
      Gems/ROS2/Code/Source/RobotImporter/URDF/PrefabMakerUtils.cpp
  22. 1 1
      Gems/ROS2/Code/Source/RobotImporter/URDF/URDFPrefabMaker.cpp
  23. 5 5
      Gems/ROS2/Code/Source/RobotImporter/URDF/VisualsMaker.cpp
  24. 4 4
      Gems/ROS2/Code/Source/RobotImporter/URDF/VisualsMaker.h
  25. 1 1
      Gems/ROS2/Code/Source/RobotImporter/Utils/RobotImporterUtils.cpp
  26. 1 1
      Gems/ROS2/Code/Source/Spawner/ROS2SpawnPointComponent.cpp
  27. 1 1
      Gems/ROS2/Code/Source/Spawner/ROS2SpawnPointComponent.h
  28. 2 2
      Gems/ROS2/Code/Source/Spawner/ROS2SpawnerComponent.cpp
  29. 5 5
      Gems/ROS2/Code/Source/VehicleDynamics/DriveModels/AckermannDriveModel.cpp
  30. 2 1
      Gems/ROS2/Code/Source/VehicleDynamics/ManualControlEventHandler.h
  31. 2 2
      Gems/ROS2/Code/Source/VehicleDynamics/Utilities.cpp
  32. 1 1
      Gems/ROS2/Code/Source/VehicleDynamics/VehicleInputsState.h
  33. 1 1
      Gems/ROS2/Code/Source/VehicleDynamics/VehicleModelComponent.cpp
  34. 16 10
      Gems/ROS2/Code/ros2_editor_files.cmake
  35. 31 37
      Gems/ROS2/Code/ros2_files.cmake

+ 3 - 7
Gems/ROS2/Code/CMakeLists.txt

@@ -27,8 +27,6 @@ ly_add_target(
     FILES_CMAKE
         ros2_header_files.cmake
         ros2_files.cmake
-    PLATFORM_INCLUDE_FILES
-        ${CMAKE_CURRENT_LIST_DIR}/Platform/Common/${PAL_TRAIT_COMPILER_ID}/ros2_static_${PAL_TRAIT_COMPILER_ID_LOWERCASE}.cmake
     INCLUDE_DIRECTORIES
         PUBLIC
             Include
@@ -88,7 +86,7 @@ if(PAL_TRAIT_BUILD_HOST_TOOLS)
         FILES_CMAKE
             ros2_editor_files.cmake
         PLATFORM_INCLUDE_FILES
-            ${CMAKE_CURRENT_LIST_DIR}/Platform/Common/${PAL_TRAIT_COMPILER_ID}/ros2_static_${PAL_TRAIT_COMPILER_ID_LOWERCASE}.cmake
+            ${CMAKE_CURRENT_LIST_DIR}/Platform/Common/${PAL_TRAIT_COMPILER_ID}/ros2_static_editor_${PAL_TRAIT_COMPILER_ID_LOWERCASE}.cmake
         INCLUDE_DIRECTORIES
             PRIVATE
                 Source
@@ -114,7 +112,7 @@ if(PAL_TRAIT_BUILD_HOST_TOOLS)
             ros2_editor_files.cmake
             ros2_editor_shared_files.cmake
         PLATFORM_INCLUDE_FILES
-            ${CMAKE_CURRENT_LIST_DIR}/Platform/Common/${PAL_TRAIT_COMPILER_ID}/ros2_static_${PAL_TRAIT_COMPILER_ID_LOWERCASE}.cmake
+            ${CMAKE_CURRENT_LIST_DIR}/Platform/Common/${PAL_TRAIT_COMPILER_ID}/ros2_static_editor_${PAL_TRAIT_COMPILER_ID_LOWERCASE}.cmake
         COMPILE_DEFINITIONS
             PRIVATE
                 ROS2_EDITOR
@@ -148,8 +146,6 @@ if(PAL_TRAIT_BUILD_TESTS_SUPPORTED)
             NAMESPACE Gem
             FILES_CMAKE
                 ros2_tests_files.cmake
-            PLATFORM_INCLUDE_FILES
-                ${CMAKE_CURRENT_LIST_DIR}/Platform/Common/${PAL_TRAIT_COMPILER_ID}/ros2_static_${PAL_TRAIT_COMPILER_ID_LOWERCASE}.cmake
             INCLUDE_DIRECTORIES
                 PRIVATE
                     Tests
@@ -176,7 +172,7 @@ if(PAL_TRAIT_BUILD_TESTS_SUPPORTED)
                 FILES_CMAKE
                     ros2_editor_tests_files.cmake
                 PLATFORM_INCLUDE_FILES
-                    ${CMAKE_CURRENT_LIST_DIR}/Platform/Common/${PAL_TRAIT_COMPILER_ID}/ros2_static_${PAL_TRAIT_COMPILER_ID_LOWERCASE}.cmake
+                    ${CMAKE_CURRENT_LIST_DIR}/Platform/Common/${PAL_TRAIT_COMPILER_ID}/ros2_static_editor_${PAL_TRAIT_COMPILER_ID_LOWERCASE}.cmake
                 INCLUDE_DIRECTORIES
                     PRIVATE
                         Tests

+ 0 - 0
Gems/ROS2/Code/Platform/Common/Clang/ros2_static_clang.cmake → Gems/ROS2/Code/Platform/Common/Clang/ros2_static_editor_clang.cmake


+ 0 - 0
Gems/ROS2/Code/Platform/Common/GCC/ros2_static_gcc.cmake → Gems/ROS2/Code/Platform/Common/GCC/ros2_static_editor_gcc.cmake


+ 0 - 0
Gems/ROS2/Code/Platform/Common/msvc/ros2_static_msvc.cmake → Gems/ROS2/Code/Platform/Common/msvc/ros2_static_editor_msvc.cmake


+ 21 - 14
Gems/ROS2/Code/Source/Camera/CameraSensor.cpp

@@ -7,8 +7,6 @@
  */
 #include "CameraSensor.h"
 
-#include <sensor_msgs/image_encodings.hpp>
-
 #include <AzCore/Math/MatrixUtils.h>
 
 #include <Atom/RPI.Public/Base.h>
@@ -30,15 +28,25 @@ namespace ROS2
     namespace Internal
     {
 
-        // maping from ATOM to ROS/OpenCV
+        /// @FormatMappings - contains the mapping from RHI to ROS image encodings. List of supported
+        /// ROS image encodings lives in `sensor_msgs/image_encodings.hpp'
+        /// We are not including `image_encodings.hpp` since it uses exceptions.
         AZStd::unordered_map<AZ::RHI::Format, const char*> FormatMappings{
-            { AZ::RHI::Format::R8G8B8A8_UNORM, sensor_msgs::image_encodings::RGBA8 },
-            { AZ::RHI::Format::R16G16B16A16_UNORM, sensor_msgs::image_encodings::RGBA16 },
-            { AZ::RHI::Format::R32G32B32A32_FLOAT, sensor_msgs::image_encodings::TYPE_32FC4 }, // Unsuported by RVIZ2
-            { AZ::RHI::Format::R8_UNORM, sensor_msgs::image_encodings::MONO8 },
-            { AZ::RHI::Format::R16_UNORM, sensor_msgs::image_encodings::MONO16 },
-            { AZ::RHI::Format::R32_FLOAT, sensor_msgs::image_encodings::TYPE_32FC1 },
+            { AZ::RHI::Format::R8G8B8A8_UNORM, "rgba8" },     { AZ::RHI::Format::R16G16B16A16_UNORM, "rgba16" },
+            { AZ::RHI::Format::R32G32B32A32_FLOAT, "32FC4" }, // Unsuported by RVIZ2
+            { AZ::RHI::Format::R8_UNORM, "mono8" },           { AZ::RHI::Format::R16_UNORM, "mono16" },
+            { AZ::RHI::Format::R32_FLOAT, "32FC1" },
+        };
 
+        /// @BitDepth - contains the mapping from RHI to size used in `step` size computation.
+        /// It is some equivalent to `bitDepth()` function from `sensor_msgs/image_encodings.hpp`
+        AZStd::unordered_map<AZ::RHI::Format, int> BitDepth{
+            { AZ::RHI::Format::R8G8B8A8_UNORM, 4 * sizeof(uint8_t) },
+            { AZ::RHI::Format::R16G16B16A16_UNORM, 4 * sizeof(uint16_t) },
+            { AZ::RHI::Format::R32G32B32A32_FLOAT, 4 * sizeof(float) }, // Unsuported by RVIZ2
+            { AZ::RHI::Format::R8_UNORM, sizeof(uint8_t) },
+            { AZ::RHI::Format::R16_UNORM, sizeof(uint16_t) },
+            { AZ::RHI::Format::R32_FLOAT, sizeof(float) },
         };
 
     } // namespace Internal
@@ -100,7 +108,7 @@ namespace ROS2
     {
         AZ_TracePrintf("CameraSensor", "Initializing pipeline for %s", m_cameraSensorDescription.m_cameraName.c_str());
 
-        AZ::Name viewName = AZ::Name("MainCamera");
+        const AZ::Name viewName = AZ::Name("MainCamera");
         m_view = AZ::RPI::View::CreateView(viewName, AZ::RPI::View::UsageCamera);
         m_view->SetViewToClipMatrix(m_cameraSensorDescription.m_viewToClipMatrix);
         m_scene = AZ::RPI::RPISystemInterface::Get()->GetSceneByName(AZ::Name("Main"));
@@ -128,7 +136,7 @@ namespace ROS2
         m_passHierarchy.push_back("CopyToSwapChain");
 
         m_pipeline->SetDefaultView(m_view);
-        AZ::RPI::ViewPtr targetView = m_scene->GetDefaultRenderPipeline()->GetDefaultView();
+        const AZ::RPI::ViewPtr targetView = m_scene->GetDefaultRenderPipeline()->GetDefaultView();
         if (auto* fp = m_scene->GetFeatureProcessor<AZ::Render::PostProcessFeatureProcessor>())
         {
             fp->SetViewAlias(m_view, targetView);
@@ -154,7 +162,7 @@ namespace ROS2
     void CameraSensor::RequestFrame(
         const AZ::Transform& cameraPose, AZStd::function<void(const AZ::RPI::AttachmentReadback::ReadbackResult& result)> callback)
     {
-        AZ::Transform inverse = (cameraPose * kAtomToRos).GetInverse();
+        const AZ::Transform inverse = (cameraPose * kAtomToRos).GetInverse();
         m_view->SetWorldToViewMatrix(AZ::Matrix4x4::CreateFromQuaternionAndTranslation(inverse.GetRotation(), inverse.GetTranslation()));
 
         AZ::Render::FrameCaptureId captureId = AZ::Render::InvalidFrameCaptureId;
@@ -190,8 +198,7 @@ namespace ROS2
                 message.encoding = Internal::FormatMappings.at(format);
                 message.width = descriptor.m_size.m_width;
                 message.height = descriptor.m_size.m_height;
-                message.step = message.width * sensor_msgs::image_encodings::bitDepth(message.encoding) / 8 *
-                    sensor_msgs::image_encodings::numChannels(message.encoding);
+                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);

+ 1 - 2
Gems/ROS2/Code/Source/Camera/ROS2CameraSensorComponent.cpp

@@ -18,7 +18,6 @@
 #include <AzCore/Serialization/SerializeContext.h>
 
 #include <sensor_msgs/distortion_models.hpp>
-#include <sensor_msgs/image_encodings.hpp>
 
 namespace ROS2
 {
@@ -138,7 +137,7 @@ namespace ROS2
 
     void ROS2CameraSensorComponent::FrequencyTick()
     {
-        AZ::Transform transform = GetEntity()->GetTransform()->GetWorldTM();
+        const AZ::Transform transform = GetEntity()->GetTransform()->GetWorldTM();
         const auto timestamp = ROS2Interface::Get()->GetROSTimestamp();
         std_msgs::msg::Header ros_header;
         if (!m_cameraSensorsWithPublihsers.empty())

+ 1 - 1
Gems/ROS2/Code/Source/Camera/ROS2CameraSensorComponent.h

@@ -48,7 +48,7 @@ namespace ROS2
 
         //! Helper to construct PublisherSensorPtrPair with give Sensor type
         template<typename CameraType>
-        PublisherSensorPtrPair createPair(ImagePublisherPtrType publisher, const CameraSensorDescription& description)
+        PublisherSensorPtrPair createPair(ImagePublisherPtrType publisher, const CameraSensorDescription& description) const
         {
             return { publisher, AZStd::make_shared<CameraType>(description) };
         }

+ 1 - 1
Gems/ROS2/Code/Source/Clock/SimulationClock.cpp

@@ -15,7 +15,7 @@ namespace ROS2
 {
     builtin_interfaces::msg::Time SimulationClock::GetROSTimestamp() const
     {
-        auto elapsedTime = GetElapsedTimeMicroseconds();
+        const auto elapsedTime = GetElapsedTimeMicroseconds();
 
         builtin_interfaces::msg::Time timeStamp;
         timeStamp.sec = static_cast<int32_t>(elapsedTime / 1000000);

+ 2 - 2
Gems/ROS2/Code/Source/Frame/ROS2FrameComponent.cpp

@@ -34,7 +34,7 @@ namespace ROS2
 
         const ROS2FrameComponent* GetFirstROS2FrameAncestor(const AZ::Entity* entity)
         {
-            AZ::TransformInterface* entityTransformInterface = GetEntityTransformInterface(entity);
+            auto* entityTransformInterface = GetEntityTransformInterface(entity);
             if (!entityTransformInterface)
             {
                 AZ_Error("GetFirstROS2FrameAncestor", false, "Invalid transform interface!");
@@ -126,7 +126,7 @@ namespace ROS2
 
     const AZ::Transform& ROS2FrameComponent::GetFrameTransform() const
     {
-        auto transformInterface = Internal::GetEntityTransformInterface(GetEntity());
+        auto* transformInterface = Internal::GetEntityTransformInterface(GetEntity());
         if (GetParentROS2FrameComponent() != nullptr)
         {
             return transformInterface->GetLocalTM();

+ 5 - 5
Gems/ROS2/Code/Source/GNSS/GNSSFormatConversions.cpp

@@ -45,11 +45,11 @@ namespace ROS2::GNSS
 
     AZ::Vector3 ECEFToENU(const AZ::Vector3& referenceLatitudeLongitudeAltitude, const AZ::Vector3& ECEFPoint)
     {
-        AZ::Vector3 referencePointInECEF = WGS84ToECEF(referenceLatitudeLongitudeAltitude);
-        AZ::Vector3 pointToReferencePointECEF = ECEFPoint - referencePointInECEF;
+        const AZ::Vector3 referencePointInECEF = WGS84ToECEF(referenceLatitudeLongitudeAltitude);
+        const AZ::Vector3 pointToReferencePointECEF = ECEFPoint - referencePointInECEF;
 
-        float referenceLatitudeRad = Deg2Rad(referenceLatitudeLongitudeAltitude.GetX());
-        float referenceLongitudeRad = Deg2Rad(referenceLatitudeLongitudeAltitude.GetY());
+        const float referenceLatitudeRad = Deg2Rad(referenceLatitudeLongitudeAltitude.GetX());
+        const float referenceLongitudeRad = Deg2Rad(referenceLatitudeLongitudeAltitude.GetY());
 
         return {
             -AZStd::sin(referenceLongitudeRad) * pointToReferencePointECEF.GetX() +
@@ -93,7 +93,7 @@ namespace ROS2::GNSS
         const double F = 54.0f * earthSemiminorAxis * earthSemiminorAxis * z * z;
         const double G = radiusSquared + (1.0f - firstEccentricitySquared) * z * z - firstEccentricitySquared * E2;
         const double c = (firstEccentricitySquared * firstEccentricitySquared * F * radiusSquared) / (G * G * G);
-        const double s = std::cbrt(1.0f + c + AZStd::sqrt(c * c + 2.0f * c));
+        const double s = AZStd::pow(1. + c + AZStd::sqrt(c * c + 2. * c), 1. / 3);
         const double P = F / (3.0f * (s + 1.0f / s + 1.0f) * (s + 1.0f / s + 1.0f) * G * G);
         const double Q = AZStd::sqrt(1.0f + 2.0f * firstEccentricitySquared * firstEccentricitySquared * P);
 

+ 1 - 1
Gems/ROS2/Code/Source/Lidar/LidarRaycaster.cpp

@@ -28,7 +28,7 @@ namespace ROS2
         const AZ::Transform& globalToLidarTM,
         float distance,
         bool ignoreLayer,
-        unsigned int ignoredLayerIndex)
+        unsigned int ignoredLayerIndex) const
     {
         AZStd::vector<AZ::Vector3> results;
         if (m_sceneHandle == AzPhysics::InvalidSceneHandle)

+ 1 - 1
Gems/ROS2/Code/Source/Lidar/LidarRaycaster.h

@@ -46,7 +46,7 @@ namespace ROS2
             const AZ::Transform& globalToLidarTM,
             float distance,
             bool ignoreLayer,
-            unsigned int ignoredLayerIndex);
+            unsigned int ignoredLayerIndex) const;
 
         //! If true the raycaster will also include points at maximum range when nothing was hit
         void SetAddPointsMaxRange(bool addPointsMaxRange);

+ 1 - 1
Gems/ROS2/Code/Source/Lidar/ROS2LidarSensorComponent.cpp

@@ -176,7 +176,7 @@ namespace ROS2
 
             // TODO - improve performance
             m_visualisationPoints = m_lastScanResults;
-            for (auto& point : m_visualisationPoints)
+            for (AZ::Vector3& point : m_visualisationPoints)
             {
                 point = localToWorldTM.TransformPoint(point);
             }

+ 2 - 2
Gems/ROS2/Code/Source/ROS2GemUtilities.cpp

@@ -15,8 +15,8 @@ namespace ROS2
 
     AZ::ComponentId Utils::CreateComponent(const AZ::EntityId entityId, const AZ::Uuid componentType)
     {
-        AZ::ComponentTypeList componentsToAdd{ componentType };
-        AZStd::vector<AZ::EntityId> entityIds{ entityId };
+        const AZ::ComponentTypeList componentsToAdd{ componentType };
+        const AZStd::vector<AZ::EntityId> entityIds{ entityId };
         AzToolsFramework::EntityCompositionRequests::AddComponentsOutcome addComponentsOutcome = AZ::Failure(AZStd::string());
         AzToolsFramework::EntityCompositionRequestBus::BroadcastResult(
             addComponentsOutcome, &AzToolsFramework::EntityCompositionRequests::AddComponentsToEntities, entityIds, componentsToAdd);

+ 1 - 1
Gems/ROS2/Code/Source/RobotImporter/URDF/CollidersMaker.cpp

@@ -343,7 +343,7 @@ namespace ROS2
     }
 
     void CollidersMaker::AddColliderToEntity(
-        urdf::CollisionSharedPtr collision, AZ::EntityId entityId, const AZ::Data::Asset<Physics::MaterialAsset>& materialAsset)
+        urdf::CollisionSharedPtr collision, AZ::EntityId entityId, const AZ::Data::Asset<Physics::MaterialAsset>& materialAsset) const
     {
         // TODO - we are unable to set collider origin. Sub-entities don't work since they would need to parent visuals etc.
         // TODO - solution: once Collider Component supports Cylinder Shape, switch to it from Shape Collider Component.

+ 1 - 1
Gems/ROS2/Code/Source/RobotImporter/URDF/CollidersMaker.h

@@ -51,7 +51,7 @@ namespace ROS2
             const AZStd::string& generatedName,
             const AZ::Data::Asset<Physics::MaterialAsset>& materialAsset);
         void AddColliderToEntity(
-            urdf::CollisionSharedPtr collision, AZ::EntityId entityId, const AZ::Data::Asset<Physics::MaterialAsset>& materialAsset);
+            urdf::CollisionSharedPtr collision, AZ::EntityId entityId, const AZ::Data::Asset<Physics::MaterialAsset>& materialAsset) const;
 
         AZStd::string m_modelPath;
 

+ 1 - 1
Gems/ROS2/Code/Source/RobotImporter/URDF/InertialsMaker.cpp

@@ -19,7 +19,7 @@ namespace ROS2
     constexpr AZ::u8 kMinimalNumPosSolv = 40;
     constexpr AZ::u8 kMinimalNumVelSolv = 10;
 
-    void InertialsMaker::AddInertial(urdf::InertialSharedPtr inertial, AZ::EntityId entityId)
+    void InertialsMaker::AddInertial(urdf::InertialSharedPtr inertial, AZ::EntityId entityId) const
     {
         if (!inertial)
         { // it is ok not to have inertia in a link

+ 1 - 1
Gems/ROS2/Code/Source/RobotImporter/URDF/InertialsMaker.h

@@ -20,6 +20,6 @@ namespace ROS2
         //! Add zero or one inertial elements to a given entity (depending on link content).
         //! @param inertial A pointer to a parsed URDF inertial structure, might be null.
         //! @param entityId A non-active entity which will be populated according to inertial content.
-        void AddInertial(urdf::InertialSharedPtr inertial, AZ::EntityId entityId);
+        void AddInertial(urdf::InertialSharedPtr inertial, AZ::EntityId entityId) const;
     };
 } // namespace ROS2

+ 1 - 1
Gems/ROS2/Code/Source/RobotImporter/URDF/JointsMaker.cpp

@@ -19,7 +19,7 @@ namespace ROS2
 {
 
     JointsMaker::JointsMakerResult JointsMaker::AddJointComponent(
-        urdf::JointSharedPtr joint, AZ::EntityId followColliderEntityId, AZ::EntityId leadColliderEntityId)
+        urdf::JointSharedPtr joint, AZ::EntityId followColliderEntityId, AZ::EntityId leadColliderEntityId) const
     {
         AZ::Entity* followColliderEntity = AzToolsFramework::GetEntityById(followColliderEntityId);
         PhysX::EditorJointComponent* jointComponent = nullptr;

+ 1 - 1
Gems/ROS2/Code/Source/RobotImporter/URDF/JointsMaker.h

@@ -28,6 +28,6 @@ namespace ROS2
         //! @param leadColliderEntityId An entity higher in hierarchy which is connected through the joint with the child entity.
         //! @returns created components Id or string with fail
         JointsMakerResult AddJointComponent(
-            urdf::JointSharedPtr joint, AZ::EntityId followColliderEntityId, AZ::EntityId leadColliderEntityId);
+            urdf::JointSharedPtr joint, AZ::EntityId followColliderEntityId, AZ::EntityId leadColliderEntityId) const;
     };
 } // namespace ROS2

+ 1 - 1
Gems/ROS2/Code/Source/RobotImporter/URDF/PrefabMakerUtils.cpp

@@ -67,7 +67,7 @@ namespace ROS2::PrefabMakerUtils
 
     AzToolsFramework::Prefab::PrefabEntityResult CreateEntity(AZ::EntityId parentEntityId, const AZStd::string& name)
     {
-        auto prefabInterface = AZ::Interface<AzToolsFramework::Prefab::PrefabPublicInterface>::Get();
+        auto* prefabInterface = AZ::Interface<AzToolsFramework::Prefab::PrefabPublicInterface>::Get();
         auto createEntityResult = prefabInterface->CreateEntity(parentEntityId, AZ::Vector3());
         if (!createEntityResult.IsSuccess())
         {

+ 1 - 1
Gems/ROS2/Code/Source/RobotImporter/URDF/URDFPrefabMaker.cpp

@@ -63,7 +63,7 @@ namespace ROS2
         }
         // TODO - this is PoC code, restructure when developing semantics of URDF->Prefab/Entities/Components mapping
         AZStd::unordered_map<AZStd::string, AzToolsFramework::Prefab::PrefabEntityResult> created_links;
-        auto createEntityRoot = AddEntitiesForLink(m_model->root_link_, AZ::EntityId());
+        AzToolsFramework::Prefab::PrefabEntityResult createEntityRoot = AddEntitiesForLink(m_model->root_link_, AZ::EntityId());
         AZStd::string root_name(m_model->root_link_->name.c_str(), m_model->root_link_->name.size());
         created_links[root_name] = createEntityRoot;
         if (!createEntityRoot.IsSuccess())

+ 5 - 5
Gems/ROS2/Code/Source/RobotImporter/URDF/VisualsMaker.cpp

@@ -37,7 +37,7 @@ namespace ROS2
         AZ_Assert(!m_modelPath.empty(), "modelPath path is empty");
     }
 
-    void VisualsMaker::AddVisuals(urdf::LinkSharedPtr link, AZ::EntityId entityId)
+    void VisualsMaker::AddVisuals(urdf::LinkSharedPtr link, AZ::EntityId entityId) const
     {
         const AZStd::string typeString = "visual";
         if (link->visual_array.size() < 1)
@@ -54,7 +54,7 @@ namespace ROS2
         }
     }
 
-    void VisualsMaker::AddVisual(urdf::VisualSharedPtr visual, AZ::EntityId entityId, const AZStd::string& generatedName)
+    void VisualsMaker::AddVisual(urdf::VisualSharedPtr visual, AZ::EntityId entityId, const AZStd::string& generatedName) const
     {
         if (!visual)
         { // it is ok not to have a visual in a link
@@ -83,7 +83,7 @@ namespace ROS2
         AddMaterialForVisual(visual, visualEntityId);
     }
 
-    void VisualsMaker::AddVisualToEntity(urdf::VisualSharedPtr visual, AZ::EntityId entityId)
+    void VisualsMaker::AddVisualToEntity(urdf::VisualSharedPtr visual, AZ::EntityId entityId) const
     {
         // Apply transform as per origin
         PrefabMakerUtils::SetEntityTransformLocal(visual->origin, entityId);
@@ -174,7 +174,7 @@ namespace ROS2
         }
     }
 
-    void VisualsMaker::AddMaterialForVisual(urdf::VisualSharedPtr visual, AZ::EntityId entityId)
+    void VisualsMaker::AddMaterialForVisual(urdf::VisualSharedPtr visual, AZ::EntityId entityId) const
     {
         // URDF does not include information from <gazebo> tags with specific materials, diffuse, specular and emissive params
         if (!visual->material || !visual->geometry)
@@ -188,7 +188,7 @@ namespace ROS2
         const AZStd::string material_name{ visual->material->name.c_str() };
 
         // If present in map, take map color definition as priority, otherwise apply local node definition
-        const auto materialColorUrdf = m_materials.contains(material_name) ? m_materials[material_name]->color : visual->material->color;
+        const auto materialColorUrdf = m_materials.contains(material_name) ? m_materials.at(material_name)->color : visual->material->color;
 
         const AZ::Color materialColor = URDF::TypeConversions::ConvertColor(materialColorUrdf);
         bool isPrimitive = visual->geometry->type != urdf::Geometry::MESH;

+ 4 - 4
Gems/ROS2/Code/Source/RobotImporter/URDF/VisualsMaker.h

@@ -25,12 +25,12 @@ namespace ROS2
         //! Note that a sub-entity will be added to hold each visual (since they can have different transforms).
         //! @param link A parsed URDF tree link node which could hold information about visuals.
         //! @param entityId A non-active entity which will be affected.
-        void AddVisuals(urdf::LinkSharedPtr link, AZ::EntityId entityId);
+        void AddVisuals(urdf::LinkSharedPtr link, AZ::EntityId entityId) const;
 
     private:
-        void AddVisual(urdf::VisualSharedPtr visual, AZ::EntityId entityId, const AZStd::string& generatedName);
-        void AddVisualToEntity(urdf::VisualSharedPtr visual, AZ::EntityId entityId);
-        void AddMaterialForVisual(urdf::VisualSharedPtr visual, AZ::EntityId entityId);
+        void AddVisual(urdf::VisualSharedPtr visual, AZ::EntityId entityId, const AZStd::string& generatedName) const;
+        void AddVisualToEntity(urdf::VisualSharedPtr visual, AZ::EntityId entityId) const;
+        void AddMaterialForVisual(urdf::VisualSharedPtr visual, AZ::EntityId entityId) const;
 
         AZ::IO::Path m_modelPath; // TODO - this should be handled on level of assets
         AZStd::unordered_map<AZStd::string, urdf::MaterialSharedPtr> m_materials;

+ 1 - 1
Gems/ROS2/Code/Source/RobotImporter/Utils/RobotImporterUtils.cpp

@@ -57,7 +57,7 @@ namespace ROS2
         std::function<void(const std::vector<urdf::LinkSharedPtr>&)> link_visitor =
             [&](const std::vector<urdf::LinkSharedPtr>& child_links) -> void
         {
-            for (auto child_link : child_links)
+            for (const urdf::LinkSharedPtr& child_link : child_links)
             {
                 AZStd::string link_name(child_link->name.c_str(), child_link->name.size());
                 pointers[link_name] = child_link;

+ 1 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnPointComponent.cpp

@@ -47,7 +47,7 @@ namespace ROS2
         }
     }
 
-    AZStd::pair<AZStd::string, SpawnPointInfo> ROS2SpawnPointComponent::GetInfo()
+    AZStd::pair<AZStd::string, SpawnPointInfo> ROS2SpawnPointComponent::GetInfo() const
     {
         auto transform_component = GetEntity()->FindComponent<AzFramework::TransformComponent>();
 

+ 1 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnPointComponent.h

@@ -34,7 +34,7 @@ namespace ROS2
 
         static void Reflect(AZ::ReflectContext* context);
 
-        AZStd::pair<AZStd::string, SpawnPointInfo> GetInfo();
+        AZStd::pair<AZStd::string, SpawnPointInfo> GetInfo() const;
 
     private:
         AZStd::string m_name;

+ 2 - 2
Gems/ROS2/Code/Source/Spawner/ROS2SpawnerComponent.cpp

@@ -225,12 +225,12 @@ namespace ROS2
 
         AZStd::unordered_map<AZStd::string, SpawnPointInfo> result;
 
-        for (const auto child : children)
+        for (const AZ::EntityId& child : children)
         {
             AZ::Entity* child_entity = nullptr;
             AZ::ComponentApplicationBus::BroadcastResult(child_entity, &AZ::ComponentApplicationRequests::FindEntity, child);
             AZ_Assert(child_entity, "No child entity %s", child.ToString().c_str());
-            auto spawn_point = child_entity->FindComponent<ROS2SpawnPointComponent>();
+            const auto* spawn_point = child_entity->FindComponent<ROS2SpawnPointComponent>();
 
             if (spawn_point == nullptr)
             {

+ 5 - 5
Gems/ROS2/Code/Source/VehicleDynamics/DriveModels/AckermannDriveModel.cpp

@@ -73,20 +73,20 @@ namespace VehicleDynamics
     {
         const double deltaTimeSec = double(deltaTimeNs) / 1e9;
 
-        auto steeringEntity = wheelData.m_steeringEntity;
+        const auto& steeringEntity = wheelData.m_steeringEntity;
         AZ::Vector3 currentSteeringElementRotation;
         AZ::TransformBus::EventResult(currentSteeringElementRotation, steeringEntity, &AZ::TransformBus::Events::GetLocalRotation);
-        auto currentSteeringAngle = currentSteeringElementRotation.Dot(wheelData.m_turnAxis);
-        double pidCommand = m_steeringPid.ComputeCommand(steering - currentSteeringAngle, deltaTimeNs);
+        const float currentSteeringAngle = currentSteeringElementRotation.Dot(wheelData.m_turnAxis);
+        const double pidCommand = m_steeringPid.ComputeCommand(steering - currentSteeringAngle, deltaTimeNs);
         if (AZ::IsClose(pidCommand, 0.0)) // TODO - use the third argument with some reasonable value which means "close enough"
         {
             return;
         }
 
-        auto torque = pidCommand * deltaTimeSec;
+        const float torque = pidCommand * deltaTimeSec;
         AZ::Transform steeringElementTransform;
         AZ::TransformBus::EventResult(steeringElementTransform, steeringEntity, &AZ::TransformBus::Events::GetWorldTM);
-        auto transformedTorqueVector = steeringElementTransform.TransformVector(wheelData.m_turnAxis * torque);
+        const auto transformedTorqueVector = steeringElementTransform.TransformVector(wheelData.m_turnAxis * torque);
         Physics::RigidBodyRequestBus::Event(steeringEntity, &Physics::RigidBodyRequests::ApplyAngularImpulse, transformedTorqueVector);
     }
 

+ 2 - 1
Gems/ROS2/Code/Source/VehicleDynamics/ManualControlEventHandler.h

@@ -8,6 +8,7 @@
 #pragma once
 
 #include "ROS2/VehicleDynamics/VehicleInputControlBus.h"
+#include <AzCore/std/function/function_template.h>
 #include <StartingPointInput/InputEventNotificationBus.h>
 
 // TODO - plenty of boilerplate code, seems somewhat redundant since it would be better to be able to map inputs directly
@@ -17,7 +18,7 @@ namespace VehicleDynamics
     class ManualControlSingleEventHandler : private StartingPointInput::InputEventNotificationBus::Handler
     {
     public:
-        using OnHeldHandlerFunction = std::function<void(float)>;
+        using OnHeldHandlerFunction = AZStd::function<void(float)>;
 
         //! Construct the event handler.
         //! @param eventName which event to handle (e.g. "steering", "accelerate")

+ 2 - 2
Gems/ROS2/Code/Source/VehicleDynamics/Utilities.cpp

@@ -98,14 +98,14 @@ namespace VehicleDynamics::Utilities
     AZStd::vector<VehicleDynamics::WheelDynamicsData> GetAllDriveWheelsData(const VehicleConfiguration& vehicleConfig)
     {
         AZStd::vector<VehicleDynamics::WheelDynamicsData> driveWheelEntities;
-        for (const auto& axle : vehicleConfig.m_axles)
+        for (const AxleConfiguration& axle : vehicleConfig.m_axles)
         {
             if (!axle.m_isDrive)
             { // Get only drive wheels, which are attached to a drive axle
                 continue;
             }
 
-            for (const auto& wheel : axle.m_axleWheels)
+            for (const AZ::EntityId& wheel : axle.m_axleWheels)
             {
                 if (!wheel.IsValid())
                 {

+ 1 - 1
Gems/ROS2/Code/Source/VehicleDynamics/VehicleInputsState.h

@@ -22,7 +22,7 @@ namespace VehicleDynamics
     */
 
     //! Inputs with an expiration date - effectively is zero after a certain time since update
-    template<typename T, typename = typename std::enable_if<std::is_arithmetic<T>::value, T>::type>
+    template<typename T, typename = typename AZStd::enable_if<AZStd::is_arithmetic<T>::value, T>::type>
     class InputZeroedOnTimeout
     {
     public:

+ 1 - 1
Gems/ROS2/Code/Source/VehicleDynamics/VehicleModelComponent.cpp

@@ -116,7 +116,7 @@ namespace VehicleDynamics
 
     void VehicleModelComponent::OnTick(float deltaTime, [[maybe_unused]] AZ::ScriptTimePoint time)
     {
-        uint64_t deltaTimeNs = deltaTime * 1'000'000'000;
+        const uint64_t deltaTimeNs = deltaTime * 1'000'000'000;
         m_driveModel.ApplyInputState(m_inputsState, deltaTimeNs);
     }
 } // namespace VehicleDynamics

+ 16 - 10
Gems/ROS2/Code/ros2_editor_files.cmake

@@ -7,24 +7,30 @@ set(FILES
     Source/ROS2EditorSystemComponent.cpp
     Source/ROS2EditorSystemComponent.h
     Source/ROS2GemUtilities.cpp
-    Source/RobotImporter/URDF/RobotImporter.cpp
-    Source/RobotImporter/URDF/RobotImporter.h
-    Source/RobotImporter/ROS2RobotImporterEditorSystemComponent.cpp
-    Source/RobotImporter/ROS2RobotImporterEditorSystemComponent.h
     Source/RobotImporter/RobotImporterWidget.cpp
     Source/RobotImporter/RobotImporterWidget.h
     Source/RobotImporter/RobotImporterWidgetUtils.cpp
     Source/RobotImporter/RobotImporterWidgetUtils.h
-    Source/RobotImporter/URDF/URDFPrefabMaker.cpp
-    Source/RobotImporter/URDF/URDFPrefabMaker.h
-    Source/RobotImporter/URDF/VisualsMaker.cpp
-    Source/RobotImporter/URDF/VisualsMaker.h
+    Source/RobotImporter/ROS2RobotImporterEditorSystemComponent.cpp
+    Source/RobotImporter/ROS2RobotImporterEditorSystemComponent.h
     Source/RobotImporter/URDF/CollidersMaker.cpp
     Source/RobotImporter/URDF/CollidersMaker.h
     Source/RobotImporter/URDF/InertialsMaker.cpp
-    Source/RobotImporter/URDF/InertialsMaker.cpp
+    Source/RobotImporter/URDF/InertialsMaker.h
     Source/RobotImporter/URDF/JointsMaker.cpp
     Source/RobotImporter/URDF/JointsMaker.h
     Source/RobotImporter/URDF/PrefabMakerUtils.cpp
-    Source/RobotImporter/URDF/PrefabMakerUtils.cpp
+    Source/RobotImporter/URDF/PrefabMakerUtils.h
+    Source/RobotImporter/URDF/RobotImporter.cpp
+    Source/RobotImporter/URDF/RobotImporter.h
+    Source/RobotImporter/URDF/UrdfParser.cpp
+    Source/RobotImporter/URDF/UrdfParser.h
+    Source/RobotImporter/URDF/URDFPrefabMaker.cpp
+    Source/RobotImporter/URDF/URDFPrefabMaker.h
+    Source/RobotImporter/URDF/VisualsMaker.cpp
+    Source/RobotImporter/URDF/VisualsMaker.h
+    Source/RobotImporter/Utils/RobotImporterUtils.cpp
+    Source/RobotImporter/Utils/RobotImporterUtils.h
+    Source/RobotImporter/Utils/TypeConversions.cpp
+    Source/RobotImporter/Utils/TypeConversions.h
 )

+ 31 - 37
Gems/ROS2/Code/ros2_files.cmake

@@ -15,6 +15,17 @@ set(FILES
         Source/Camera/ROS2CameraSensorComponent.h
         Source/Clock/SimulationClock.cpp
         Source/Clock/SimulationClock.h
+        Source/Communication/QoS.cpp
+        Source/Communication/TopicConfiguration.cpp
+        Source/Frame/NamespaceConfiguration.cpp
+        Source/Frame/ROS2FrameComponent.cpp
+        Source/Frame/ROS2Transform.cpp
+        Source/GNSS/GNSSFormatConversions.cpp
+        Source/GNSS/GNSSFormatConversions.h
+        Source/GNSS/ROS2GNSSSensorComponent.cpp
+        Source/GNSS/ROS2GNSSSensorComponent.h
+        Source/Imu/ROS2ImuSensorComponent.cpp
+        Source/Imu/ROS2ImuSensorComponent.h
         Source/Lidar/LidarRaycaster.cpp
         Source/Lidar/LidarRaycaster.h
         Source/Lidar/LidarTemplate.cpp
@@ -24,24 +35,26 @@ set(FILES
         Source/Lidar/ROS2LidarSensorComponent.cpp
         Source/Lidar/ROS2LidarSensorComponent.h
         Source/Manipulator/MotorizedJoint.cpp
-        Source/Communication/QoS.cpp
-        Source/Communication/TopicConfiguration.cpp
-        Source/RobotControl/ControlConfiguration.cpp
-        Source/RobotControl/ControlConfiguration.h
-        Source/RobotControl/ControlSubscriptionHandler.h
-        Source/RobotControl/ROS2RobotControlComponent.cpp
-        Source/RobotControl/ROS2RobotControlComponent.h
+        Source/Odometry/ROS2OdometrySensorComponent.cpp
+        Source/Odometry/ROS2OdometrySensorComponent.h
         Source/RobotControl/Ackermann/AckermannBus.h
         Source/RobotControl/Ackermann/AckermannCommandStruct.h
         Source/RobotControl/Ackermann/AckermannSubscriptionHandler.cpp
         Source/RobotControl/Ackermann/AckermannSubscriptionHandler.h
+        Source/RobotControl/ControlConfiguration.cpp
+        Source/RobotControl/ControlConfiguration.h
         Source/RobotControl/Controllers/AckermannController/AckermannControlComponent.cpp
         Source/RobotControl/Controllers/AckermannController/AckermannControlComponent.h
         Source/RobotControl/Controllers/RigidBodyController/RigidBodyTwistControlComponent.cpp
         Source/RobotControl/Controllers/RigidBodyController/RigidBodyTwistControlComponent.h
+        Source/RobotControl/ControlSubscriptionHandler.h
+        Source/RobotControl/ROS2RobotControlComponent.cpp
+        Source/RobotControl/ROS2RobotControlComponent.h
         Source/RobotControl/Twist/TwistBus.h
         Source/RobotControl/Twist/TwistSubscriptionHandler.cpp
         Source/RobotControl/Twist/TwistSubscriptionHandler.h
+        Source/RobotImporter/ROS2RobotImporterSystemComponent.cpp
+        Source/RobotImporter/ROS2RobotImporterSystemComponent.h
         Source/ROS2ModuleInterface.h
         Source/ROS2SystemComponent.cpp
         Source/ROS2SystemComponent.h
@@ -49,40 +62,26 @@ set(FILES
         Source/Sensor/ROS2SensorComponent.h
         Source/Sensor/SensorConfiguration.cpp
         Source/Sensor/SensorConfiguration.h
-        Source/Frame/NamespaceConfiguration.cpp
-        Source/Frame/ROS2FrameComponent.cpp
-        Source/Frame/ROS2Transform.cpp
+        Source/Spawner/ROS2SpawnerComponent.cpp
+        Source/Spawner/ROS2SpawnerComponent.h
+        Source/Spawner/ROS2SpawnPointComponent.cpp
+        Source/Spawner/ROS2SpawnPointComponent.h
+        Source/Spawner/SpawnerBus.h
         Source/Utilities/ROS2Conversions.cpp
         Source/Utilities/ROS2Names.cpp
-        Source/GNSS/ROS2GNSSSensorComponent.cpp
-        Source/GNSS/ROS2GNSSSensorComponent.h
-        Source/GNSS/GNSSFormatConversions.cpp
-        Source/GNSS/GNSSFormatConversions.h
-        Source/Imu/ROS2ImuSensorComponent.cpp
-        Source/Imu/ROS2ImuSensorComponent.h
-        Source/Odometry/ROS2OdometrySensorComponent.cpp
-        Source/Odometry/ROS2OdometrySensorComponent.h
-        Source/RobotImporter/ROS2RobotImporterSystemComponent.cpp
-        Source/RobotImporter/ROS2RobotImporterSystemComponent.h
-        Source/RobotImporter/Utils/RobotImporterUtils.h
-        Source/RobotImporter/Utils/RobotImporterUtils.cpp
-        Source/RobotImporter/Utils/TypeConversions.h
-        Source/RobotImporter/Utils/TypeConversions.cpp
-        Source/RobotImporter/URDF/UrdfParser.cpp
-        Source/RobotImporter/URDF/UrdfParser.h
-        Source/VehicleDynamics/DriveModels/PidConfiguration.cpp
-        Source/VehicleDynamics/DriveModels/AckermannDriveModel.cpp
-        Source/VehicleDynamics/DriveModels/AckermannDriveModel.h
         Source/VehicleDynamics/AxleConfiguration.cpp
         Source/VehicleDynamics/AxleConfiguration.h
-        Source/VehicleDynamics/VehicleConfiguration.cpp
-        Source/VehicleDynamics/VehicleConfiguration.h
         Source/VehicleDynamics/DriveModel.cpp
         Source/VehicleDynamics/DriveModel.h
+        Source/VehicleDynamics/DriveModels/AckermannDriveModel.cpp
+        Source/VehicleDynamics/DriveModels/AckermannDriveModel.h
+        Source/VehicleDynamics/DriveModels/PidConfiguration.cpp
         Source/VehicleDynamics/ManualControlEventHandler.h
-        Source/VehicleDynamics/VehicleInputsState.h
         Source/VehicleDynamics/Utilities.cpp
         Source/VehicleDynamics/Utilities.h
+        Source/VehicleDynamics/VehicleConfiguration.cpp
+        Source/VehicleDynamics/VehicleConfiguration.h
+        Source/VehicleDynamics/VehicleInputsState.h
         Source/VehicleDynamics/VehicleModelComponent.cpp
         Source/VehicleDynamics/VehicleModelComponent.h
         Source/VehicleDynamics/VehicleModelLimits.cpp
@@ -90,9 +89,4 @@ set(FILES
         Source/VehicleDynamics/WheelControllerComponent.cpp
         Source/VehicleDynamics/WheelControllerComponent.h
         Source/VehicleDynamics/WheelDynamicsData.h
-        Source/Spawner/ROS2SpawnerComponent.h
-        Source/Spawner/ROS2SpawnerComponent.cpp
-        Source/Spawner/ROS2SpawnPointComponent.cpp
-        Source/Spawner/ROS2SpawnPointComponent.h
-        Source/Spawner/SpawnerBus.h
         )