Bläddra i källkod

Re-enable Skid and Ackermann model hooks in RobotImporter Gem (#922)

Signed-off-by: Jan Hanca <[email protected]>
Jan Hanca 1 månad sedan
förälder
incheckning
866ed57d49
39 ändrade filer med 569 tillägg och 233 borttagningar
  1. 10 1
      Gems/ROS2Controllers/Code/Include/ROS2Controllers/Controllers/PidConfiguration.h
  2. 127 0
      Gems/ROS2Controllers/Code/Include/ROS2Controllers/ROS2ControllersEditorBus.h
  3. 2 2
      Gems/ROS2Controllers/Code/Include/ROS2Controllers/ROS2ControllersTypeIds.h
  4. 11 0
      Gems/ROS2Controllers/Code/Include/ROS2Controllers/VehicleDynamics/AxleConfiguration.h
  5. 0 0
      Gems/ROS2Controllers/Code/Include/ROS2Controllers/VehicleDynamics/VehicleConfiguration.h
  6. 1 1
      Gems/ROS2Controllers/Code/Source/RobotControl/Controllers/SkidSteeringController/SkidSteeringControlComponent.h
  7. 98 3
      Gems/ROS2Controllers/Code/Source/Tools/ROS2ControllersEditorSystemComponent.cpp
  8. 75 0
      Gems/ROS2Controllers/Code/Source/Tools/ROS2ControllersEditorSystemComponent.h
  9. 0 17
      Gems/ROS2Controllers/Code/Source/Utilities/Controllers/PidConfiguration.cpp
  10. 1 1
      Gems/ROS2Controllers/Code/Source/VehicleDynamics/AxleConfiguration.cpp
  11. 1 1
      Gems/ROS2Controllers/Code/Source/VehicleDynamics/DriveModel.h
  12. 2 2
      Gems/ROS2Controllers/Code/Source/VehicleDynamics/DriveModels/AckermannDriveModel.h
  13. 1 1
      Gems/ROS2Controllers/Code/Source/VehicleDynamics/DriveModels/SkidSteeringDriveModel.h
  14. 9 6
      Gems/ROS2Controllers/Code/Source/VehicleDynamics/ModelLimits/SkidSteeringModelLimits.cpp
  15. 2 2
      Gems/ROS2Controllers/Code/Source/VehicleDynamics/ModelLimits/SkidSteeringModelLimits.h
  16. 2 2
      Gems/ROS2Controllers/Code/Source/VehicleDynamics/Utilities.h
  17. 1 1
      Gems/ROS2Controllers/Code/Source/VehicleDynamics/VehicleConfiguration.cpp
  18. 2 1
      Gems/ROS2Controllers/Code/Source/VehicleDynamics/VehicleModelComponent.cpp
  19. 1 1
      Gems/ROS2Controllers/Code/Source/VehicleDynamics/VehicleModelComponent.h
  20. 2 0
      Gems/ROS2Controllers/Code/ros2controllers_api_files.cmake
  21. 1 0
      Gems/ROS2Controllers/Code/ros2controllers_editor_api_files.cmake
  22. 0 2
      Gems/ROS2Controllers/Code/ros2controllers_private_files.cmake
  23. 1 1
      Gems/ROS2Controllers/gem.json
  24. 2 0
      Gems/ROS2RobotImporter/Code/CMakeLists.txt
  25. 43 36
      Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2AckermannModelHook.cpp
  26. 2 2
      Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2CameraSensorHook.cpp
  27. 2 2
      Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2GNSSSensorHook.cpp
  28. 2 2
      Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2ImuSensorHook.cpp
  29. 14 11
      Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2JointPoseTrajectoryModelHook.cpp
  30. 13 8
      Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2JointStatePublisherModelHook.cpp
  31. 4 3
      Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2LidarSensorHook.cpp
  32. 53 41
      Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2SkidSteeringModelHook.cpp
  33. 8 10
      Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/ROS2ModelPluginHooks.h
  34. 4 5
      Gems/ROS2RobotImporter/Code/Source/Tools/ROS2RobotImporterEditorSystemComponent.cpp
  35. 63 60
      Gems/ROS2RobotImporter/Code/Tests/SdfParserTest.cpp
  36. 4 5
      Gems/ROS2RobotImporter/Code/ros2robotimporter_editor_private_files.cmake
  37. 2 1
      Gems/ROS2RobotImporter/gem.json
  38. 2 1
      Gems/ROS2Sensors/Code/Source/Tools/ROS2SensorsEditorSystemComponent.cpp
  39. 1 1
      Gems/ROS2Sensors/gem.json

+ 10 - 1
Gems/ROS2Controllers/Code/Include/ROS2Controllers/Controllers/PidConfiguration.h

@@ -36,7 +36,16 @@ namespace ROS2Controllers
             const double iMax,
             const double iMin,
             const bool antiWindup,
-            const double outputLimit);
+            const double outputLimit)
+            : m_p(p)
+            , m_i(i)
+            , m_d(d)
+            , m_iMax(iMax)
+            , m_iMin(iMin)
+            , m_antiWindup(antiWindup)
+            , m_outputLimit(outputLimit)
+        {
+        }
 
         //! Initialize the controller
         void InitializePid();

+ 127 - 0
Gems/ROS2Controllers/Code/Include/ROS2Controllers/ROS2ControllersEditorBus.h

@@ -0,0 +1,127 @@
+/*
+ * Copyright (c) Contributors to the Open 3D Engine Project.
+ * For complete copyright and license terms please see the LICENSE at the root of this distribution.
+ *
+ * SPDX-License-Identifier: Apache-2.0 OR MIT
+ *
+ */
+
+#pragma once
+
+#include <ROS2/Communication/PublisherConfiguration.h>
+#include <ROS2Controllers/Controllers/PidConfiguration.h>
+#include <ROS2Controllers/ROS2ControllersTypeIds.h>
+#include <ROS2Controllers/RobotControl/ControlConfiguration.h>
+#include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
+
+#include <AzCore/Component/Component.h>
+#include <AzCore/EBus/EBus.h>
+#include <AzCore/Interface/Interface.h>
+#include <AzCore/std/string/string.h>
+
+namespace ROS2Controllers
+{
+    //! Interface for creating ROS2 controller components.
+    //! This interface provides methods to create various types of ROS2 controller components, such as wheel controllers, robot control,
+    //! vehicle models, and joint controllers.
+    //! It is intended to be used by external tools that create entities, e.g., when importing robots from SDF, URDF, or OpenUSD.
+    class ROS2ControllersEditorRequests
+    {
+    public:
+        AZ_RTTI(ROS2ControllersEditorRequests, ROS2ControllersEditorRequestsTypeId);
+        virtual ~ROS2ControllersEditorRequests() = default;
+
+        //! Create a new Wheel Controller component.
+        //! @param entity The entity to which the wheel controller component will be added.
+        //! @param steeringEntity The entity that will be used for steering control (WheelControllerComponent parameter).
+        //! @param steeringScale The scale factor for the steering control (WheelControllerComponent parameter).
+        //! @return A pointer to the newly created AZ::Component representing the Wheel Controller (or nullptr if failed).
+        virtual AZ::Component* CreateWheelControllerComponent(
+            AZ::Entity& entity, const AZ::EntityId& steeringEntity, const float steeringScale) = 0;
+
+        //! Create a new ROS2 Robot Control component.
+        //! @param entity The entity to which the robot control component will be added.
+        //! @param configuration The configuration for the robot control.
+        //! @return A pointer to the newly created AZ::Component representing the ROS2 Robot Control (or nullptr if failed).
+        virtual AZ::Component* CreateROS2RobotControlComponent(AZ::Entity& entity, const ControlConfiguration& configuration) = 0;
+
+        //! Create a new Ackermann Vehicle Model component.
+        //! @param entity The entity to which the vehicle model component will be added.
+        //! @param configuration The configuration for the Ackermann vehicle model.
+        //! @param speedLimit The maximum speed limit for the vehicle model.
+        //! @param steeringLimit The maximum steering limit for the vehicle model.
+        //! @param acceleration The maximum acceleration for the vehicle model.
+        //! @param steeringPid The PID configuration for the steering control.
+        //! @return A pointer to the newly created AZ::Component representing the Ackermann Vehicle Model (or nullptr if failed).
+        virtual AZ::Component* CreateAckermannVehicleModelComponent(
+            AZ::Entity& entity,
+            const VehicleDynamics::VehicleConfiguration& configuration,
+            const float speedLimit,
+            const float steeringLimit,
+            const float acceleration,
+            const PidConfiguration& steeringPid) = 0;
+
+        //! Create a new Ackermann Control component.
+        //! @param entity The entity to which the control component will be added.
+        //! @return A pointer to the newly created AZ::Component representing the Ackermann Control (or nullptr if failed).
+        virtual AZ::Component* CreateAckermannControlComponent(AZ::Entity& entity) = 0;
+
+        //! Create a new Skid Steering Model component.
+        //! @param entity The entity to which the skid steering model component will be added.
+        //! @param configuration The configuration for the skid steering vehicle model.
+        //! @param linearLimit The maximum linear speed limit for the skid steering model [m/s].
+        //! @param angularLimit The maximum angular speed limit for the skid steering model [Rad/s].
+        //! @param linearAcceleration The maximum linear acceleration for the skid steering model [m*s^(-2)].
+        //! @param angularAcceleration The maximum angular acceleration for the skid steering model [rad*s^(-2)].
+        //! @return A pointer to the newly created AZ::Component representing the Skid Steering Model (or nullptr if failed).
+        virtual AZ::Component* CreateSkidSteeringModelComponent(
+            AZ::Entity& entity,
+            const VehicleDynamics::VehicleConfiguration& configuration,
+            const float linearLimit,
+            const float angularLimit,
+            const float linearAcceleration,
+            const float angularAcceleration) = 0;
+
+        //! Create a new Skid Steering Control component.
+        //! @param entity The entity to which the control component will be added.
+        //! @return A pointer to the newly created AZ::Component representing the Skid Steering Control (or nullptr if failed).
+        virtual AZ::Component* CreateSkidSteeringControlComponent(AZ::Entity& entity) = 0;
+
+        //! Create a new Joints Articulation Controller component.
+        //! @param entity The entity to which the Joints Articulation Controller component will be added.
+        //! @return A pointer to the newly created AZ::Component representing the Joints Articulation Controller (or nullptr if failed).
+        virtual AZ::Component* CreateJointsArticulationControllerComponent(AZ::Entity& entity) = 0;
+
+        //! Create a new Joints PID Controller component.
+        //! @param entity The entity to which the Joints PID Controller component will be added.
+        //! @return A pointer to the newly created AZ::Component representing the Joints PID Controller (or nullptr if failed).
+        virtual AZ::Component* CreateJointsPIDControllerComponent(AZ::Entity& entity) = 0;
+
+        //! Create a new Joints Manipulation Editor component.
+        //! @param entity The entity to which the Joints Manipulation Editor component will be added.
+        //! @param publisherConfig The publisher configuration for the Joints Manipulation Editor component.
+        //! @return A pointer to the newly created AZ::Component representing the Joints Manipulation Editor (or nullptr if failed).
+        virtual AZ::Component* CreateJointsManipulationEditorComponent(
+            AZ::Entity& entity, const ROS2::PublisherConfiguration& publisherConfig) = 0;
+
+        //! Create a new Joints Trajectory component.
+        //! @param entity The entity to which the Joints Trajectory component will be added.
+        //! @param actionName The name of the trajectory action to be used by the Joints Trajectory component.
+        //! @return A pointer to the newly created AZ::Component representing the Joints Trajectory (or nullptr if failed).
+        virtual AZ::Component* CreateJointsTrajectoryComponent(AZ::Entity& entity, const AZStd::string& actionName) = 0;
+    };
+
+    class ROS2ControllersEditorBusTraits : public AZ::EBusTraits
+    {
+    public:
+        //////////////////////////////////////////////////////////////////////////
+        // EBusTraits overrides
+        static constexpr AZ::EBusHandlerPolicy HandlerPolicy = AZ::EBusHandlerPolicy::Single;
+        static constexpr AZ::EBusAddressPolicy AddressPolicy = AZ::EBusAddressPolicy::Single;
+        //////////////////////////////////////////////////////////////////////////
+    };
+
+    using ROS2ControllersEditorRequestBus = AZ::EBus<ROS2ControllersEditorRequests, ROS2ControllersEditorBusTraits>;
+    using ROS2ControllersEditorInterface = AZ::Interface<ROS2ControllersEditorRequests>;
+
+} // namespace ROS2Controllers

+ 2 - 2
Gems/ROS2Controllers/Code/Include/ROS2Controllers/ROS2ControllersTypeIds.h

@@ -22,8 +22,8 @@ namespace ROS2Controllers
     // so they use the Same TypeId
     inline constexpr const char* ROS2ControllersEditorModuleTypeId = ROS2ControllersModuleTypeId;
 
-    // Interface TypeIds
-    inline constexpr const char* ROS2ControllersRequestsTypeId = "{2E0AB230-743E-4BCA-8194-D1BC7C9341EA}";
+    // Editor Interface TypeIds
+    inline constexpr const char* ROS2ControllersEditorRequestsTypeId = "{2E0AB230-743E-4BCA-8194-D1BC7C9341EA}";
 
     // Sensors TypeIds
     inline constexpr const char* ROS2WheelOdometryComponentTypeId = "{9BDB8C23-AC76-4C25-8D35-37AAA9F43FAC}";

+ 11 - 0
Gems/ROS2Controllers/Code/Source/VehicleDynamics/AxleConfiguration.h → Gems/ROS2Controllers/Code/Include/ROS2Controllers/VehicleDynamics/AxleConfiguration.h

@@ -20,6 +20,17 @@ namespace ROS2Controllers::VehicleDynamics
     public:
         AZ_TYPE_INFO(AxleConfiguration, "{75BD5FEA-EADE-4371-8B2C-96F05A886BEB}");
         AxleConfiguration() = default;
+
+        //! Create the most common two wheel axle out of existing wheel entities.
+        AxleConfiguration(AZ::EntityId leftWheel, AZ::EntityId rightWheel, AZStd::string tag, float wheelRadius, bool steering, bool drive)
+            : m_axleWheels({ leftWheel, rightWheel })
+            , m_axleTag(AZStd::move(tag))
+            , m_wheelRadius(wheelRadius)
+            , m_isSteering(steering)
+            , m_isDrive(drive)
+        {
+        }
+
         static void Reflect(AZ::ReflectContext* context);
 
         // Helper functions for wheel entities. If there is only one wheel, same value is returned from both.

+ 0 - 0
Gems/ROS2Controllers/Code/Source/VehicleDynamics/VehicleConfiguration.h → Gems/ROS2Controllers/Code/Include/ROS2Controllers/VehicleDynamics/VehicleConfiguration.h


+ 1 - 1
Gems/ROS2Controllers/Code/Source/RobotControl/Controllers/SkidSteeringController/SkidSteeringControlComponent.h

@@ -10,7 +10,7 @@
 
 #include <AzCore/Component/Component.h>
 #include <ROS2Controllers/RobotControl/Twist/TwistBus.h>
-#include <VehicleDynamics/AxleConfiguration.h>
+#include <ROS2Controllers/VehicleDynamics/AxleConfiguration.h>
 #include <VehicleDynamics/Utilities.h>
 
 namespace ROS2Controllers

+ 98 - 3
Gems/ROS2Controllers/Code/Source/Tools/ROS2ControllersEditorSystemComponent.cpp

@@ -10,7 +10,18 @@
 #include "ROS2ControllersEditorSystemComponent.h"
 #include <AzCore/Serialization/SerializeContext.h>
 
+#include <Manipulation/Controllers/JointsArticulationControllerComponent.h>
+#include <Manipulation/Controllers/JointsPIDControllerComponent.h>
+#include <Manipulation/JointsManipulationEditorComponent.h>
+#include <Manipulation/JointsTrajectoryComponent.h>
 #include <ROS2Controllers/ROS2ControllersTypeIds.h>
+#include <RobotControl/Controllers/AckermannController/AckermannControlComponent.h>
+#include <RobotControl/Controllers/SkidSteeringController/SkidSteeringControlComponent.h>
+#include <RobotControl/ROS2RobotControlComponent.h>
+#include <VehicleDynamics/ModelComponents/AckermannModelComponent.h>
+#include <VehicleDynamics/ModelComponents/SkidSteeringModelComponent.h>
+#include <VehicleDynamics/ModelLimits/AckermannModelLimits.h>
+#include <VehicleDynamics/WheelControllerComponent.h>
 
 namespace ROS2Controllers
 {
@@ -24,13 +35,26 @@ namespace ROS2Controllers
     {
         if (auto serializeContext = azrtti_cast<AZ::SerializeContext*>(context))
         {
-            serializeContext->Class<ROS2ControllersEditorSystemComponent, ROS2ControllersSystemComponent>()->Version(0);
+            serializeContext->Class<ROS2ControllersEditorSystemComponent, ROS2ControllersSystemComponent>()->Version(1)->Attribute(
+                AZ::Edit::Attributes::SystemComponentTags, AZStd::vector<AZ::Crc32>({ AZ_CRC_CE("AssetBuilder") }));
         }
     }
 
-    ROS2ControllersEditorSystemComponent::ROS2ControllersEditorSystemComponent() = default;
+    ROS2ControllersEditorSystemComponent::ROS2ControllersEditorSystemComponent()
+    {
+        if (ROS2ControllersEditorInterface::Get() == nullptr)
+        {
+            ROS2ControllersEditorInterface::Register(this);
+        }
+    }
 
-    ROS2ControllersEditorSystemComponent::~ROS2ControllersEditorSystemComponent() = default;
+    ROS2ControllersEditorSystemComponent::~ROS2ControllersEditorSystemComponent()
+    {
+        if (ROS2ControllersEditorInterface::Get() == this)
+        {
+            ROS2ControllersEditorInterface::Unregister(this);
+        }
+    }
 
     void ROS2ControllersEditorSystemComponent::GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided)
     {
@@ -67,4 +91,75 @@ namespace ROS2Controllers
         ROS2ControllersSystemComponent::Deactivate();
     }
 
+    AZ::Component* ROS2ControllersEditorSystemComponent::CreateWheelControllerComponent(
+        AZ::Entity& entity, const AZ::EntityId& steeringEntity, const float steeringScale)
+    {
+        return CreateComponent<VehicleDynamics::WheelControllerComponent>(entity, steeringEntity, steeringScale);
+    }
+
+    AZ::Component* ROS2ControllersEditorSystemComponent::CreateROS2RobotControlComponent(
+        AZ::Entity& entity, const ControlConfiguration& configuration)
+    {
+        return CreateComponent<ROS2Controllers::ROS2RobotControlComponent>(entity, configuration);
+    }
+
+    AZ::Component* ROS2ControllersEditorSystemComponent::CreateAckermannVehicleModelComponent(
+        AZ::Entity& entity,
+        const VehicleDynamics::VehicleConfiguration& configuration,
+        const float speedLimit,
+        const float steeringLimit,
+        const float acceleration,
+        const PidConfiguration& steeringPid)
+    {
+        VehicleDynamics::AckermannModelLimits modelLimits(speedLimit, steeringLimit, acceleration);
+
+        return CreateComponent<VehicleDynamics::AckermannVehicleModelComponent>(
+            entity, configuration, VehicleDynamics::AckermannDriveModel(modelLimits, steeringPid));
+    }
+
+    AZ::Component* ROS2ControllersEditorSystemComponent::CreateAckermannControlComponent(AZ::Entity& entity)
+    {
+        return CreateComponent<AckermannControlComponent>(entity);
+    }
+
+    AZ::Component* ROS2ControllersEditorSystemComponent::CreateSkidSteeringModelComponent(
+        AZ::Entity& entity,
+        const VehicleDynamics::VehicleConfiguration& configuration,
+        const float linearLimit,
+        const float angularLimit,
+        const float linearAcceleration,
+        const float angularAcceleration)
+    {
+        VehicleDynamics::SkidSteeringModelLimits modelLimits(linearLimit, angularLimit, linearAcceleration, angularAcceleration);
+
+        return CreateComponent<VehicleDynamics::SkidSteeringModelComponent>(
+            entity, configuration, VehicleDynamics::SkidSteeringDriveModel(modelLimits));
+    }
+
+    AZ::Component* ROS2ControllersEditorSystemComponent::CreateSkidSteeringControlComponent(AZ::Entity& entity)
+    {
+        return CreateComponent<ROS2Controllers::SkidSteeringControlComponent>(entity);
+    }
+
+    AZ::Component* ROS2ControllersEditorSystemComponent::CreateJointsArticulationControllerComponent(AZ::Entity& entity)
+    {
+        return CreateComponent<ROS2Controllers::JointsArticulationControllerComponent>(entity);
+    }
+
+    AZ::Component* ROS2ControllersEditorSystemComponent::CreateJointsPIDControllerComponent(AZ::Entity& entity)
+    {
+        return CreateComponent<ROS2Controllers::JointsPIDControllerComponent>(entity);
+    }
+
+    AZ::Component* ROS2ControllersEditorSystemComponent::CreateJointsManipulationEditorComponent(
+        AZ::Entity& entity, const ROS2::PublisherConfiguration& publisherConfig)
+    {
+        return CreateComponent<ROS2Controllers::JointsManipulationEditorComponent>(entity, publisherConfig);
+    }
+
+    AZ::Component* ROS2ControllersEditorSystemComponent::CreateJointsTrajectoryComponent(
+        AZ::Entity& entity, const AZStd::string& actionName)
+    {
+        return CreateComponent<ROS2Controllers::JointsTrajectoryComponent>(entity, actionName);
+    }
 } // namespace ROS2Controllers

+ 75 - 0
Gems/ROS2Controllers/Code/Source/Tools/ROS2ControllersEditorSystemComponent.h

@@ -9,9 +9,14 @@
 
 #pragma once
 
+#include <AzCore/Component/Component.h>
+#include <AzCore/Component/Entity.h>
 #include <AzToolsFramework/API/ToolsApplicationAPI.h>
+#include <AzToolsFramework/ToolsComponents/EditorComponentBase.h>
+#include <AzToolsFramework/ToolsComponents/GenericComponentWrapper.h>
 
 #include <Clients/ROS2ControllersSystemComponent.h>
+#include <ROS2Controllers/ROS2ControllersEditorBus.h>
 
 namespace ROS2Controllers
 {
@@ -19,6 +24,7 @@ namespace ROS2Controllers
     class ROS2ControllersEditorSystemComponent
         : public ROS2ControllersSystemComponent
         , protected AzToolsFramework::EditorEvents::Bus::Handler
+        , protected ROS2ControllersEditorRequestBus::Handler
     {
         using BaseSystemComponent = ROS2ControllersSystemComponent;
 
@@ -30,6 +36,35 @@ namespace ROS2Controllers
         ROS2ControllersEditorSystemComponent();
         ~ROS2ControllersEditorSystemComponent();
 
+    protected:
+        ////////////////////////////////////////////////////////////////////////
+        // ROS2ControllersEditorRequestBus interface implementation
+        AZ::Component* CreateWheelControllerComponent(
+            AZ::Entity& entity, const AZ::EntityId& steeringEntity, const float steeringScale) override;
+        AZ::Component* CreateROS2RobotControlComponent(AZ::Entity& entity, const ControlConfiguration& configuration) override;
+        AZ::Component* CreateAckermannVehicleModelComponent(
+            AZ::Entity& entity,
+            const VehicleDynamics::VehicleConfiguration& configuration,
+            const float speedLimit,
+            const float steeringLimit,
+            const float acceleration,
+            const PidConfiguration& steeringPid) override;
+        AZ::Component* CreateAckermannControlComponent(AZ::Entity& entity) override;
+        AZ::Component* CreateSkidSteeringModelComponent(
+            AZ::Entity& entity,
+            const VehicleDynamics::VehicleConfiguration& configuration,
+            const float linearLimit,
+            const float angularLimit,
+            const float linearAcceleration,
+            const float angularAcceleration) override;
+        AZ::Component* CreateSkidSteeringControlComponent(AZ::Entity& entity) override;
+        AZ::Component* CreateJointsArticulationControllerComponent(AZ::Entity& entity) override;
+        AZ::Component* CreateJointsPIDControllerComponent(AZ::Entity& entity) override;
+        AZ::Component* CreateJointsManipulationEditorComponent(
+            AZ::Entity& entity, const ROS2::PublisherConfiguration& publisherConfig) override;
+        AZ::Component* CreateJointsTrajectoryComponent(AZ::Entity& entity, const AZStd::string& actionName) override;
+        ////////////////////////////////////////////////////////////////////////
+
     private:
         static void GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided);
         static void GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible);
@@ -39,5 +74,45 @@ namespace ROS2Controllers
         // AZ::Component
         void Activate() override;
         void Deactivate() override;
+
+        //! Create a component and attach the component to the entity.
+        //! This method ensures that game components are wrapped into GenericComponentWrapper.
+        //! @param entity entity to which the new component is added
+        //! @param args constructor arguments used to create the new component
+        //! @return A pointer to the component. Returns a null pointer if the component could not be created.
+        template<class ComponentType, typename... Args>
+        AZ::Component* CreateComponent(AZ::Entity& entity, Args&&... args)
+        {
+            // Do not create a component if the same type is already added.
+            if (entity.FindComponent<ComponentType>())
+            {
+                return nullptr;
+            }
+
+            // Create component.
+            // If it's not an "editor component" then wrap it in a GenericComponentWrapper.
+            AZ::Component* component = nullptr;
+            if (AZ::GetRttiHelper<ComponentType>() &&
+                AZ::GetRttiHelper<ComponentType>()->IsTypeOf(AzToolsFramework::Components::EditorComponentBase::RTTI_Type()))
+            {
+                component = aznew ComponentType(AZStd::forward<Args>(args)...);
+            }
+            else
+            {
+                AZ::Component* gameComponent = aznew ComponentType(AZStd::forward<Args>(args)...);
+                component = aznew AzToolsFramework::Components::GenericComponentWrapper(gameComponent);
+            }
+
+            AZ_Assert(component, "Failed to create component: %s", AZ::AzTypeInfo<ComponentType>::Name());
+            if (component)
+            {
+                if (!entity.IsComponentReadyToAdd(component) || !entity.AddComponent(component))
+                {
+                    delete component;
+                    component = nullptr;
+                }
+            }
+            return component;
+        }
     };
 } // namespace ROS2Controllers

+ 0 - 17
Gems/ROS2Controllers/Code/Source/Utilities/Controllers/PidConfiguration.cpp

@@ -51,23 +51,6 @@ namespace ROS2Controllers
             }
         }
     }
-    PidConfiguration::PidConfiguration(
-        const double p,
-        const double i,
-        const double d,
-        const double iMax,
-        const double iMin,
-        const bool antiWindup,
-        const double outputLimit)
-        : m_p(p)
-        , m_i(i)
-        , m_d(d)
-        , m_iMax(iMax)
-        , m_iMin(iMin)
-        , m_antiWindup(antiWindup)
-        , m_outputLimit(outputLimit)
-    {
-    }
 
     void PidConfiguration::InitializePid()
     {

+ 1 - 1
Gems/ROS2Controllers/Code/Source/VehicleDynamics/AxleConfiguration.cpp

@@ -6,9 +6,9 @@
  *
  */
 
-#include "AxleConfiguration.h"
 #include <AzCore/Serialization/EditContext.h>
 #include <AzCore/Serialization/EditContextConstants.inl>
+#include <ROS2Controllers/VehicleDynamics/AxleConfiguration.h>
 
 namespace ROS2Controllers::VehicleDynamics
 {

+ 1 - 1
Gems/ROS2Controllers/Code/Source/VehicleDynamics/DriveModel.h

@@ -7,10 +7,10 @@
  */
 #pragma once
 
-#include "VehicleConfiguration.h"
 #include "VehicleInputs.h"
 #include <AzCore/Serialization/SerializeContext.h>
 #include <AzCore/std/utils.h>
+#include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
 #include <VehicleDynamics/VehicleModelLimits.h>
 
 namespace ROS2Controllers::VehicleDynamics

+ 2 - 2
Gems/ROS2Controllers/Code/Source/VehicleDynamics/DriveModels/AckermannDriveModel.h

@@ -9,9 +9,9 @@
 
 #include <AzCore/Serialization/SerializeContext.h>
 #include <ROS2Controllers/Controllers/PidConfiguration.h>
-#include <VehicleDynamics/DriveModel.h>
+#include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
 #include <VehicleDynamics/ModelLimits/AckermannModelLimits.h>
-#include <VehicleDynamics/VehicleConfiguration.h>
+#include <VehicleDynamics/DriveModel.h>
 #include <VehicleDynamics/VehicleInputs.h>
 #include <VehicleDynamics/WheelDynamicsData.h>
 

+ 1 - 1
Gems/ROS2Controllers/Code/Source/VehicleDynamics/DriveModels/SkidSteeringDriveModel.h

@@ -11,8 +11,8 @@
 #include <AzCore/Serialization/SerializeContext.h>
 #include <VehicleDynamics/DriveModel.h>
 
+#include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
 #include <VehicleDynamics/ModelLimits/SkidSteeringModelLimits.h>
-#include <VehicleDynamics/VehicleConfiguration.h>
 #include <VehicleDynamics/VehicleInputs.h>
 #include <VehicleDynamics/WheelControllerComponent.h>
 #include <VehicleDynamics/WheelDynamicsData.h>

+ 9 - 6
Gems/ROS2Controllers/Code/Source/VehicleDynamics/ModelLimits/SkidSteeringModelLimits.cpp

@@ -61,6 +61,15 @@ namespace ROS2Controllers::VehicleDynamics
         }
     }
 
+    SkidSteeringModelLimits::SkidSteeringModelLimits(
+        const float linearLimit, const float angularLimit, const float linearAcceleration, const float angularAcceleration)
+    {
+        m_linearLimit = AZStd::clamp(linearLimit, 0.0f, 100.0f);
+        m_angularLimit = AZStd::clamp(angularLimit, 0.0f, 10.0f);
+        m_linearAcceleration = AZStd::clamp(linearAcceleration, 0.0f, 100.0f);
+        m_angularAcceleration = AZStd::clamp(angularAcceleration, 0.0f, 100.0f);
+    }
+
     VehicleInputs SkidSteeringModelLimits::LimitState(const VehicleInputs& inputState) const
     {
         VehicleInputs ret = inputState;
@@ -96,10 +105,4 @@ namespace ROS2Controllers::VehicleDynamics
     {
         return m_angularLimit;
     }
-
-    void SkidSteeringModelLimits::SetAngularAccelerationLimit(const float limit)
-    {
-        m_angularAcceleration = AZStd::clamp(limit, 0.0f, 100.0f);
-    }
-
 } // namespace ROS2Controllers::VehicleDynamics

+ 2 - 2
Gems/ROS2Controllers/Code/Source/VehicleDynamics/ModelLimits/SkidSteeringModelLimits.h

@@ -21,6 +21,8 @@ namespace ROS2Controllers::VehicleDynamics
     public:
         AZ_RTTI(SkidSteeringModelLimits, "{23420EFB-BB62-48C7-AD37-E50580A53C39}", VehicleModelLimits);
         SkidSteeringModelLimits() = default;
+        SkidSteeringModelLimits(
+            const float linearLimit, const float angularLimit, const float linearAcceleration, const float angularAcceleration);
 
         static void Reflect(AZ::ReflectContext* context);
 
@@ -33,8 +35,6 @@ namespace ROS2Controllers::VehicleDynamics
         float GetLinearSpeedLimit() const;
         float GetAngularSpeedLimit() const;
 
-        void SetAngularAccelerationLimit(const float limit);
-
     private:
         float m_linearLimit = 2.0f; //!< [m/s] Maximum travel velocity.
         float m_angularLimit = 3.5f; //!< [Rad/s] Maximum rotation speed.

+ 2 - 2
Gems/ROS2Controllers/Code/Source/VehicleDynamics/Utilities.h

@@ -7,13 +7,13 @@
  */
 #pragma once
 
-#include "AxleConfiguration.h"
-#include "VehicleConfiguration.h"
 #include "WheelDynamicsData.h"
 #include <AzCore/Component/ComponentBus.h>
 #include <AzCore/Component/EntityId.h>
 #include <AzCore/std/containers/vector.h>
 #include <AzCore/std/string/string.h>
+#include <ROS2Controllers/VehicleDynamics/AxleConfiguration.h>
+#include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
 
 namespace ROS2Controllers::VehicleDynamics::Utilities
 {

+ 1 - 1
Gems/ROS2Controllers/Code/Source/VehicleDynamics/VehicleConfiguration.cpp

@@ -6,12 +6,12 @@
  *
  */
 
-#include "VehicleConfiguration.h"
 #include "Utilities.h"
 #include <AzCore/Debug/Trace.h>
 #include <AzCore/Serialization/EditContext.h>
 #include <AzCore/Serialization/EditContextConstants.inl>
 #include <AzCore/Serialization/SerializeContext.h>
+#include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
 
 namespace ROS2Controllers::VehicleDynamics
 {

+ 2 - 1
Gems/ROS2Controllers/Code/Source/VehicleDynamics/VehicleModelComponent.cpp

@@ -9,7 +9,6 @@
 #include "VehicleModelComponent.h"
 #include "DriveModels/AckermannDriveModel.h"
 #include "Utilities.h"
-#include "VehicleConfiguration.h"
 #include "VehicleModelLimits.h"
 #include <AzCore/Debug/Trace.h>
 #include <AzCore/Serialization/EditContext.h>
@@ -17,6 +16,8 @@
 #include <AzCore/Serialization/SerializeContext.h>
 #include <AzCore/std/smart_ptr/make_shared.h>
 #include <AzFramework/Physics/RigidBodyBus.h>
+#include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
+
 namespace ROS2Controllers::VehicleDynamics
 {
     void VehicleModelComponent::Activate()

+ 1 - 1
Gems/ROS2Controllers/Code/Source/VehicleDynamics/VehicleModelComponent.h

@@ -9,12 +9,12 @@
 
 #include "DriveModels/AckermannDriveModel.h"
 #include "ManualControlEventHandler.h"
-#include "VehicleConfiguration.h"
 #include "VehicleInputs.h"
 #include <AzCore/Component/Component.h>
 #include <AzCore/Component/TickBus.h>
 #include <AzCore/std/smart_ptr/unique_ptr.h>
 #include <AzCore/std/utils.h>
+#include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
 #include <ROS2Controllers/VehicleDynamics/VehicleInputControlBus.h>
 #include <VehicleDynamics/VehicleModelLimits.h>
 

+ 2 - 0
Gems/ROS2Controllers/Code/ros2controllers_api_files.cmake

@@ -24,5 +24,7 @@ set(FILES
     Include/ROS2Controllers/Sensors/ROS2OdometryCovariance.h
     Include/ROS2Controllers/Sensors/WheelOdometrySensorConfiguration.h
     Include/ROS2Controllers/Sensors/WheelOdometryConfigurationRequestBus.h
+    Include/ROS2Controllers/VehicleDynamics/AxleConfiguration.h
+    Include/ROS2Controllers/VehicleDynamics/VehicleConfiguration.h
     Include/ROS2Controllers/VehicleDynamics/VehicleInputControlBus.h
 )

+ 1 - 0
Gems/ROS2Controllers/Code/ros2controllers_editor_api_files.cmake

@@ -7,4 +7,5 @@
 #
 
 set(FILES
+    Include/ROS2Controllers/ROS2ControllersEditorBus.h
 )

+ 0 - 2
Gems/ROS2Controllers/Code/ros2controllers_private_files.cmake

@@ -64,7 +64,6 @@ set(FILES
     Source/Utilities/JointUtilities.h
     Source/Utilities/Controllers/PidConfiguration.cpp
     Source/VehicleDynamics/AxleConfiguration.cpp
-    Source/VehicleDynamics/AxleConfiguration.h
     Source/VehicleDynamics/DriveModel.cpp
     Source/VehicleDynamics/DriveModel.h
     Source/VehicleDynamics/DriveModels/AckermannDriveModel.cpp
@@ -75,7 +74,6 @@ set(FILES
     Source/VehicleDynamics/Utilities.cpp
     Source/VehicleDynamics/Utilities.h
     Source/VehicleDynamics/VehicleConfiguration.cpp
-    Source/VehicleDynamics/VehicleConfiguration.h
     Source/VehicleDynamics/VehicleInputs.cpp
     Source/VehicleDynamics/VehicleInputs.h
     Source/VehicleDynamics/VehicleModelComponent.cpp

+ 1 - 1
Gems/ROS2Controllers/gem.json

@@ -22,7 +22,7 @@
     "documentation_url": "https://docs.o3de.org/docs/user-guide/gems/reference/robotics/ros2/",
     "dependencies": [
         "PhysX5",
-        "ROS2>=3.3.0"
+        "ROS2>=4.0.0"
     ],
     "repo_uri": "https://github.com/o3de/o3de-extras/",
     "source_control_uri": "https://github.com/o3de/o3de-extras/development/Gems/ROS2Controllers",

+ 2 - 0
Gems/ROS2RobotImporter/Code/CMakeLists.txt

@@ -150,6 +150,8 @@ if(PAL_TRAIT_BUILD_HOST_TOOLS)
                 Gem::ROS2.Static
                 Gem::ROS2.Editor.Static
                 Gem::ROS2Sensors.Editor.API
+                Gem::ROS2Controllers.API
+                Gem::ROS2Controllers.Editor.API
                 ${gem_name}.Private.Object
             PRIVATE
                 AZ::AssetBuilderSDK

+ 43 - 36
Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2AckermannModelHook.cpp

@@ -11,16 +11,15 @@
 #include <AzToolsFramework/ToolsComponents/TransformComponent.h>
 #include <PhysX/EditorColliderComponentRequestBus.h>
 #include <ROS2/Frame/ROS2FrameEditorComponent.h>
-#include <ROS2/RobotControl/ControlConfiguration.h>
-#include <RobotControl/Controllers/AckermannController/AckermannControlComponent.h>
-#include <RobotControl/ROS2RobotControlComponent.h>
+#include <ROS2Controllers/Controllers/PidConfiguration.h>
+#include <ROS2Controllers/ROS2ControllersEditorBus.h>
+#include <ROS2Controllers/RobotControl/ControlConfiguration.h>
+#include <ROS2Controllers/VehicleDynamics/AxleConfiguration.h>
+#include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
 #include <RobotImporter/SDFormat/ROS2ModelPluginHooks.h>
 #include <RobotImporter/SDFormat/ROS2SDFormatHooksUtils.h>
 #include <Source/EditorColliderComponent.h>
 #include <Source/EditorHingeJointComponent.h>
-#include <VehicleDynamics/ModelComponents/AckermannModelComponent.h>
-#include <VehicleDynamics/Utilities.h>
-#include <VehicleDynamics/WheelControllerComponent.h>
 
 #include <gz/math/Vector2.hh>
 #include <gz/math/Vector3.hh>
@@ -146,16 +145,16 @@ namespace ROS2RobotImporter::SDFormat
             return AZ::Vector3();
         }
 
-        PidConfiguration GetModelPidConfiguration(const sdf::ElementPtr element)
+        ROS2Controllers::PidConfiguration GetModelPidConfiguration(const sdf::ElementPtr element)
         {
             auto pid = element->Get<gz::math::Vector3d>("linear_velocity_pid_gain", gz::math::Vector3d::Zero).first;
             auto iRange = element->Get<gz::math::Vector2d>("linear_velocity_i_range", gz::math::Vector2d::Zero).first;
 
-            PidConfiguration config(pid.X(), pid.Y(), pid.Z(), iRange.Y(), iRange.X(), false, 0.0);
+            ROS2Controllers::PidConfiguration config(pid.X(), pid.Y(), pid.Z(), iRange.Y(), iRange.X(), false, 0.0);
             return config;
         }
 
-        VehicleDynamics::VehicleConfiguration GetConfiguration(
+        ROS2Controllers::VehicleDynamics::VehicleConfiguration GetConfiguration(
             const sdf::ElementPtr element, const sdf::Model& sdfModel, const CreatedEntitiesMap& createdEntities)
         {
             const static AZStd::array<std::string, Wheels::Total> jointNamesSDFormat{ { "front_left_joint",
@@ -189,8 +188,16 @@ namespace ROS2RobotImporter::SDFormat
                 }
             }
 
+            ROS2Controllers::VehicleDynamics::VehicleConfiguration configuration;
+            auto interface = ROS2Controllers::ROS2ControllersEditorInterface::Get();
+            if (!interface)
+            {
+                AZ_Warning(
+                    "ROS2RobotImporter", false, "ROS2ControllersInterface is not available. Cannot create wheel controller components.");
+                return configuration;
+            }
+
             bool foundSteeringWheels = false;
-            VehicleDynamics::VehicleConfiguration configuration;
             auto addAxle = [&](const unsigned int wheelIdLeft, const unsigned int wheelIdRight, AZStd::string tag) -> void
             {
                 const auto& jointLeft = jointMapper[wheelIdLeft];
@@ -203,7 +210,7 @@ namespace ROS2RobotImporter::SDFormat
                         IsSteeringWheel(jointNameSteeringRight, jointRight.m_jointName, sdfModel);
                     const bool isDrive = !isSteering;
                     const float wheelRadius = GetWheelRadius(jointLeft.m_entity, jointRight.m_entity);
-                    configuration.m_axles.emplace_back(ROS2Controllers::VehicleDynamics::Utilities::Create2WheelAxle(
+                    configuration.m_axles.emplace_back(ROS2Controllers::VehicleDynamics::AxleConfiguration(
                         jointLeft.m_entityId, jointRight.m_entityId, AZStd::move(tag), wheelRadius, isSteering, isDrive));
 
                     const float track = GetTrack(jointLeft.m_entity, jointRight.m_entity);
@@ -219,20 +226,18 @@ namespace ROS2RobotImporter::SDFormat
                     if (isSteering)
                     {
                         const auto entityIdSteeringLeft = HooksUtils::GetJointEntityId(jointNameSteeringLeft, sdfModel, createdEntities);
-                        HooksUtils::CreateComponent<VehicleDynamics::WheelControllerComponent>(
-                            jointLeft.m_entityId, entityIdSteeringLeft, 1.0f);
+                        interface->CreateWheelControllerComponent(*jointLeft.m_entity, entityIdSteeringLeft, 1.0f);
                         HooksUtils::EnableMotor(entityIdSteeringLeft);
 
                         const auto entityIdSteeringRight = HooksUtils::GetJointEntityId(jointNameSteeringRight, sdfModel, createdEntities);
-                        HooksUtils::CreateComponent<VehicleDynamics::WheelControllerComponent>(
-                            jointRight.m_entityId, entityIdSteeringRight, 1.0f);
+                        interface->CreateWheelControllerComponent(*jointRight.m_entity, entityIdSteeringRight, 1.0f);
                         HooksUtils::EnableMotor(entityIdSteeringRight);
                         foundSteeringWheels = true;
                     }
                     else
                     {
-                        HooksUtils::CreateComponent<VehicleDynamics::WheelControllerComponent>(jointLeft.m_entityId);
-                        HooksUtils::CreateComponent<VehicleDynamics::WheelControllerComponent>(jointRight.m_entityId);
+                        interface->CreateWheelControllerComponent(*jointLeft.m_entity, AZ::EntityId(), 0.0f);
+                        interface->CreateWheelControllerComponent(*jointRight.m_entity, AZ::EntityId(), 0.0f);
                     }
                     HooksUtils::EnableMotor(jointLeft.m_entityId);
                     HooksUtils::EnableMotor(jointRight.m_entityId);
@@ -268,15 +273,6 @@ namespace ROS2RobotImporter::SDFormat
 
             return configuration;
         }
-
-        VehicleDynamics::AckermannModelLimits GetModelLimits(const sdf::ElementPtr element)
-        {
-            // Set default limits as in libgazebo_ros_ackermann_drive plugin, see:
-            // https://github.com/ros-simulation/gazebo_ros_pkgs/blob/79fd94c6da76781a91499bc0f54b70560b90a9d2/gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp#L306C1-L307C65
-            const float speedLimit = element->Get<double>("max_speed", 20.0).first;
-            const float steeringLimit = element->Get<double>("max_steer", 0.6).first;
-            return VehicleDynamics::AckermannModelLimits(speedLimit, steeringLimit, speedLimit);
-        }
     } // namespace AckermannParser
 
     ModelPluginImporterHook ROS2ModelPluginHooks::ROS2AckermannModel()
@@ -294,21 +290,32 @@ namespace ROS2RobotImporter::SDFormat
         {
             // Parse parameters
             const sdf::ElementPtr element = sdfPlugin.Element();
-            VehicleDynamics::VehicleConfiguration vehicleConfiguration =
-                AckermannParser::GetConfiguration(element, sdfModel, createdEntities);
-            VehicleDynamics::AckermannModelLimits modelLimits = AckermannParser::GetModelLimits(element);
-            PidConfiguration steeringPid = AckermannParser::GetModelPidConfiguration(element);
-            ControlConfiguration controlConfiguration;
-            controlConfiguration.m_steering = ControlConfiguration::Steering::Ackermann;
+            const auto vehicleConfiguration = AckermannParser::GetConfiguration(element, sdfModel, createdEntities);
+            const auto steeringPid = AckermannParser::GetModelPidConfiguration(element);
+            ROS2Controllers::ControlConfiguration controlConfiguration;
+            controlConfiguration.m_steering = ROS2Controllers::ControlConfiguration::Steering::Ackermann;
+
+            // Set default limits as in libgazebo_ros_ackermann_drive plugin, see:
+            // https://github.com/ros-simulation/gazebo_ros_pkgs/blob/79fd94c6da76781a91499bc0f54b70560b90a9d2/gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp#L306C1-L307C65
+            const float speedLimit = element->Get<double>("max_speed", 20.0).first;
+            const float steeringLimit = element->Get<double>("max_steer", 0.6).first;
+            const float accelLimit = 100.0f; // Acceleration limit is not specified in the plugin, so we use a default value.
 
             // Create required components
+            auto* interface = ROS2Controllers::ROS2ControllersEditorInterface::Get();
+            AZ_Assert(interface, "ROS2ControllersEditorInterface not available in ROS2AckermannModelPluginHook");
+            if (!interface)
+            {
+                return AZ::Failure(AZStd::string("ROS2ControllersInterface is not available. Cannot create components."));
+            }
+
             HooksUtils::CreateComponent<ROS2::ROS2FrameEditorComponent>(entity);
-            HooksUtils::CreateComponent<ROS2Controllers::ROS2RobotControlComponent>(entity, controlConfiguration);
-            HooksUtils::CreateComponent<VehicleDynamics::AckermannVehicleModelComponent>(
-                entity, vehicleConfiguration, VehicleDynamics::AckermannDriveModel(modelLimits, steeringPid));
+            interface->CreateROS2RobotControlComponent(entity, controlConfiguration);
+            interface->CreateAckermannVehicleModelComponent(
+                entity, vehicleConfiguration, speedLimit, steeringLimit, accelLimit, steeringPid);
 
             // Create Ackermann Control Component
-            if (HooksUtils::CreateComponent<AckermannControlComponent>(entity))
+            if (interface->CreateAckermannControlComponent(entity))
             {
                 return AZ::Success();
             }

+ 2 - 2
Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2CameraSensorHook.cpp

@@ -124,8 +124,8 @@ namespace ROS2RobotImporter::SDFormat
             HooksUtils::CreateComponent<ROS2::ROS2FrameEditorComponent>(entity, frameConfiguration);
 
             // Create Camera component
-            auto interface = ROS2Sensors::ROS2SensorsEditorInterface::Get();
-            AZ_Warning("ROS2RobotImporter", interface, "ROS2SensorsInterface is not available. Cannot create Camera sensor component.");
+            auto* interface = ROS2Sensors::ROS2SensorsEditorInterface::Get();
+            AZ_Assert(interface, "ROS2SensorsEditorInterface not available in ROS2CameraSensorHook");
             if (interface)
             {
                 if (auto* sensor = interface->CreateROS2CameraSensorComponent(entity, sensorConfiguration, cameraConfiguration))

+ 2 - 2
Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2GNSSSensorHook.cpp

@@ -53,8 +53,8 @@ namespace ROS2RobotImporter::SDFormat
             HooksUtils::CreateComponent<ROS2::ROS2FrameEditorComponent>(entity, frameConfiguration);
 
             // Create GNSS component
-            auto interface = ROS2Sensors::ROS2SensorsEditorInterface::Get();
-            AZ_Warning("ROS2RobotImporter", interface, "ROS2SensorsInterface is not available. Cannot create GNSS sensor component.");
+            auto* interface = ROS2Sensors::ROS2SensorsEditorInterface::Get();
+            AZ_Assert(interface, "ROS2SensorsEditorInterface not available in ROS2GNSSSensorHook");
             if (interface)
             {
                 if (auto* sensor = interface->CreateROS2GnssSensorComponent(entity, sensorConfiguration))

+ 2 - 2
Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2ImuSensorHook.cpp

@@ -104,8 +104,8 @@ namespace ROS2RobotImporter::SDFormat
             HooksUtils::CreateComponent<PhysX::EditorArticulationLinkComponent>(entity);
 
             // Create Imu component
-            auto interface = ROS2Sensors::ROS2SensorsEditorInterface::Get();
-            AZ_Warning("ROS2RobotImporter", interface, "ROS2SensorsInterface is not available. Cannot create Imu sensor component.");
+            auto* interface = ROS2Sensors::ROS2SensorsEditorInterface::Get();
+            AZ_Assert(interface, "ROS2SensorsEditorInterface not available in ROS2ImuSensorHook");
             if (interface)
             {
                 if (auto* sensor = interface->CreateROS2ImuSensorComponent(entity, sensorConfiguration, imuConfiguration))

+ 14 - 11
Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2JointPoseTrajectoryModelHook.cpp

@@ -6,11 +6,9 @@
  *
  */
 
-#include <Manipulation/Controllers/JointsArticulationControllerComponent.h>
-#include <Manipulation/Controllers/JointsPIDControllerComponent.h>
-#include <Manipulation/JointsManipulationEditorComponent.h>
-#include <Manipulation/JointsTrajectoryComponent.h>
+#include <ROS2/Communication/PublisherConfiguration.h>
 #include <ROS2/Frame/ROS2FrameEditorComponent.h>
+#include <ROS2Controllers/ROS2ControllersEditorBus.h>
 #include <RobotImporter/SDFormat/ROS2ModelPluginHooks.h>
 #include <RobotImporter/SDFormat/ROS2SDFormatHooksUtils.h>
 #include <Source/EditorArticulationLinkComponent.h>
@@ -31,7 +29,7 @@ namespace ROS2RobotImporter::SDFormat
             const auto poseTrajectoryParams = HooksUtils::GetPluginParams({ sdfPlugin });
 
             // configure JointsManipulationEditorComponent publisher
-            PublisherConfiguration publisherConfiguration;
+            ROS2::PublisherConfiguration publisherConfiguration;
             publisherConfiguration.m_frequency = HooksUtils::GetFrequency(poseTrajectoryParams);
             publisherConfiguration.m_topicConfiguration.m_type = "sensor_msgs::msg::JointState";
             publisherConfiguration.m_topicConfiguration.m_topic = "joint_states";
@@ -45,19 +43,24 @@ namespace ROS2RobotImporter::SDFormat
             HooksUtils::CreateComponent<ROS2::ROS2FrameEditorComponent>(entity);
 
             // create controllerComponent based on model joints/articulations
-            entity.FindComponent<PhysX::EditorArticulationLinkComponent>()
-                ? HooksUtils::CreateComponent<ROS2Controllers::JointsArticulationControllerComponent>(entity)
-                : HooksUtils::CreateComponent<ROS2Controllers::JointsPIDControllerComponent>(entity);
+            auto* interface = ROS2Controllers::ROS2ControllersEditorInterface::Get();
+            AZ_Assert(interface, "ROS2ControllersEditorInterface not available in ROS2JointPoseTrajectoryModelPluginHook");
+            if (!interface)
+            {
+                return AZ::Failure(AZStd::string("ROS2ControllersInterface is not available. Cannot create components."));
+            }
 
-            HooksUtils::CreateComponent<ROS2Controllers::JointsManipulationEditorComponent>(entity, publisherConfiguration);
+            entity.FindComponent<PhysX::EditorArticulationLinkComponent>() ? interface->CreateJointsArticulationControllerComponent(entity)
+                                                                           : interface->CreateJointsPIDControllerComponent(entity);
 
-            if (HooksUtils::CreateComponent<ROS2Controllers::JointsTrajectoryComponent>(entity, trajectoryActionName))
+            interface->CreateJointsManipulationEditorComponent(entity, publisherConfiguration);
+            if (interface->CreateJointsTrajectoryComponent(entity, trajectoryActionName))
             {
                 return AZ::Success();
             }
             else
             {
-                return AZ::Failure(AZStd::string("Failed to create ROS 2 Joint Pose Trajectory Component"));
+                return AZ::Failure(AZStd::string("Failed to create ROS 2 Joints Trajectory Component"));
             }
         };
 

+ 13 - 8
Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2JointStatePublisherModelHook.cpp

@@ -8,10 +8,9 @@
 
 #include <AzCore/std/containers/vector.h>
 #include <AzCore/std/string/string.h>
-#include <Manipulation/Controllers/JointsArticulationControllerComponent.h>
-#include <Manipulation/Controllers/JointsPIDControllerComponent.h>
-#include <Manipulation/JointsManipulationEditorComponent.h>
+#include <ROS2/Communication/PublisherConfiguration.h>
 #include <ROS2/Frame/ROS2FrameEditorComponent.h>
+#include <ROS2Controllers/ROS2ControllersEditorBus.h>
 #include <RobotImporter/SDFormat/ROS2ModelPluginHooks.h>
 #include <RobotImporter/SDFormat/ROS2SDFormatHooksUtils.h>
 #include <RobotImporter/Utils/RobotImporterUtils.h>
@@ -33,7 +32,7 @@ namespace ROS2RobotImporter::SDFormat
             const auto statePublisherParams = HooksUtils::GetPluginParams({ sdfPlugin });
 
             // configure publisher
-            PublisherConfiguration publisherConfiguration;
+            ROS2::PublisherConfiguration publisherConfiguration;
             publisherConfiguration.m_frequency = HooksUtils::GetFrequency(statePublisherParams);
             publisherConfiguration.m_topicConfiguration.m_type = "sensor_msgs::msg::JointState";
 
@@ -45,11 +44,17 @@ namespace ROS2RobotImporter::SDFormat
             HooksUtils::CreateComponent<ROS2::ROS2FrameEditorComponent>(entity);
 
             // create controllerComponent based on model joints/articulations
-            entity.FindComponent<PhysX::EditorArticulationLinkComponent>()
-                ? HooksUtils::CreateComponent<ROS2Controllers::JointsArticulationControllerComponent>(entity)
-                : HooksUtils::CreateComponent<ROS2Controllers::JointsPIDControllerComponent>(entity);
+            auto* interface = ROS2Controllers::ROS2ControllersEditorInterface::Get();
+            AZ_Assert(interface, "ROS2ControllersEditorInterface not available in ROS2JointStatePublisherModelPluginHook");
+            if (!interface)
+            {
+                return AZ::Failure(AZStd::string("ROS2ControllersInterface is not available. Cannot create components."));
+            }
+
+            entity.FindComponent<PhysX::EditorArticulationLinkComponent>() ? interface->CreateJointsArticulationControllerComponent(entity)
+                                                                           : interface->CreateJointsPIDControllerComponent(entity);
 
-            if (HooksUtils::CreateComponent<ROS2Controllers::JointsManipulationEditorComponent>(entity, publisherConfiguration))
+            if (interface->CreateJointsManipulationEditorComponent(entity, publisherConfiguration))
             {
                 return AZ::Success();
             }

+ 4 - 3
Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2LidarSensorHook.cpp

@@ -84,6 +84,7 @@ namespace ROS2RobotImporter::SDFormat
             lidarConfiguration.m_lidarParameters.m_maxRange = lidarSensor->RangeMax();
 
             auto* lidarRegistrar = ROS2Sensors::LidarRegistrarInterface::Get();
+            AZ_Assert(lidarRegistrar, "lidarRegistrar not available in ROS2LidarSensorHook");
             if (lidarRegistrar)
             {
                 const auto lidarSystems = lidarRegistrar->GetRegisteredLidarSystems();
@@ -110,8 +111,8 @@ namespace ROS2RobotImporter::SDFormat
             HooksUtils::CreateComponent<ROS2::ROS2FrameEditorComponent>(entity, frameConfiguration);
 
             // Create Lidar component
-            auto interface = ROS2Sensors::ROS2SensorsEditorInterface::Get();
-            AZ_Warning("ROS2RobotImporter", interface, "ROS2SensorsInterface is not available. Cannot create Lidar sensor component.");
+            auto* interface = ROS2Sensors::ROS2SensorsEditorInterface::Get();
+            AZ_Assert(interface, "ROS2SensorsEditorInterface not available in ROS2LidarSensorHook");
             if (interface)
             {
                 if (auto* sensor = is2DLidar ? interface->CreateROS2Lidar2DSensorComponent(entity, sensorConfiguration, lidarConfiguration)
@@ -121,7 +122,7 @@ namespace ROS2RobotImporter::SDFormat
                 }
             }
 
-            return AZ::Failure(AZStd::string("Failed to create ROS 2 Imu Sensor component"));
+            return AZ::Failure(AZStd::string("Failed to create ROS 2 Lidar Sensor component"));
         };
 
         return importerHook;

+ 53 - 41
Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/Hooks/ROS2SkidSteeringModelHook.cpp

@@ -8,12 +8,13 @@
 
 #include <AzCore/Math/MathUtils.h>
 #include <ROS2/Frame/ROS2FrameEditorComponent.h>
-#include <RobotControl/Controllers/SkidSteeringController/SkidSteeringControlComponent.h>
-#include <RobotControl/ROS2RobotControlComponent.h>
+#include <ROS2Controllers/Controllers/PidConfiguration.h>
+#include <ROS2Controllers/ROS2ControllersEditorBus.h>
+#include <ROS2Controllers/RobotControl/ControlConfiguration.h>
+#include <ROS2Controllers/VehicleDynamics/AxleConfiguration.h>
+#include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
 #include <RobotImporter/SDFormat/ROS2ModelPluginHooks.h>
 #include <RobotImporter/SDFormat/ROS2SDFormatHooksUtils.h>
-#include <VehicleDynamics/ModelComponents/SkidSteeringModelComponent.h>
-#include <VehicleDynamics/Utilities.h>
 
 #include <sdf/Joint.hh>
 #include <sdf/Link.hh>
@@ -24,10 +25,10 @@ namespace ROS2RobotImporter::SDFormat
 {
     namespace SkidSteeringParser
     {
-        VehicleDynamics::VehicleConfiguration CreateVehicleConfiguration(
+        ROS2Controllers::VehicleDynamics::VehicleConfiguration CreateVehicleConfiguration(
             const sdf::ElementPtr element, const sdf::Model& sdfModel, const CreatedEntitiesMap& createdEntities)
         {
-            VehicleDynamics::VehicleConfiguration configuration;
+            ROS2Controllers::VehicleDynamics::VehicleConfiguration configuration;
             auto addAxle = [&sdfModel, &createdEntities, &configuration](
                                const std::string& jointNameLeft,
                                const std::string& jointNameRight,
@@ -38,13 +39,30 @@ namespace ROS2RobotImporter::SDFormat
                 const auto entityIdRight = HooksUtils::GetJointEntityId(jointNameRight, sdfModel, createdEntities);
                 if (entityIdLeft.IsValid() && entityIdRight.IsValid())
                 {
+                    AZ::Entity* entityLeft = nullptr;
+                    AZ::Entity* entityRight = nullptr;
+                    AZ::ComponentApplicationBus::BroadcastResult(entityLeft, &AZ::ComponentApplicationRequests::FindEntity, entityIdLeft);
+                    AZ::ComponentApplicationBus::BroadcastResult(entityRight, &AZ::ComponentApplicationRequests::FindEntity, entityIdRight);
+                    auto interface = ROS2Controllers::ROS2ControllersEditorInterface::Get();
+                    if (entityLeft && entityRight && interface)
+                    {
+                        interface->CreateWheelControllerComponent(*entityLeft, AZ::EntityId(), 0.0f);
+                        interface->CreateWheelControllerComponent(*entityRight, AZ::EntityId(), 0.0f);
+                    }
+                    else
+                    {
+                        AZ_Warning(
+                            "ROS2RobotImporter",
+                            false,
+                            "ROS2ControllersInterface is not available. Cannot create wheel controller components.");
+                    }
+
                     HooksUtils::EnableMotor(entityIdLeft);
-                    HooksUtils::CreateComponent<VehicleDynamics::WheelControllerComponent>(entityIdLeft);
                     HooksUtils::EnableMotor(entityIdRight);
-                    HooksUtils::CreateComponent<VehicleDynamics::WheelControllerComponent>(entityIdRight);
+
                     constexpr bool steering = false; // Skid steering model does not have any steering wheels.
                     constexpr bool drive = true;
-                    configuration.m_axles.emplace_back(VehicleDynamics::Utilities::Create2WheelAxle(
+                    configuration.m_axles.emplace_back(ROS2Controllers::VehicleDynamics::AxleConfiguration(
                         entityIdLeft, entityIdRight, AZStd::move(tag), wheelDiameter / 2.0f, steering, drive));
                 }
                 else
@@ -146,29 +164,10 @@ namespace ROS2RobotImporter::SDFormat
             }
 
             AZ_Warning(
-                "CreateVehicleConfiguration", !configuration.m_axles.empty(), "VehicleConfiguration parsing error: cannot find any axles.");
+                "ROS2SkidSteeringModelHook", !configuration.m_axles.empty(), "VehicleConfiguration parsing error: cannot find any axles.");
 
             return configuration;
         }
-
-        VehicleDynamics::SkidSteeringModelLimits CreateModelLimits(const sdf::ElementPtr element)
-        {
-            VehicleDynamics::SkidSteeringModelLimits modelLimits;
-            if (element->HasElement("wheelAcceleration"))
-            {
-                modelLimits.SetAngularAccelerationLimit(element->Get<float>("wheelAcceleration"));
-            }
-            else if (element->HasElement("max_wheel_acceleration"))
-            {
-                modelLimits.SetAngularAccelerationLimit(element->Get<float>("max_wheel_acceleration"));
-            }
-            else
-            {
-                AZ_Warning("CreateModelLimits", false, "VehicleConfiguration parsing error: cannot determine model limits.");
-            }
-
-            return modelLimits;
-        }
     } // namespace SkidSteeringParser
 
     ModelPluginImporterHook ROS2ModelPluginHooks::ROS2SkidSteeringModel()
@@ -176,11 +175,11 @@ namespace ROS2RobotImporter::SDFormat
         ModelPluginImporterHook importerHook;
         importerHook.m_pluginNames =
             AZStd::unordered_set<AZStd::string>{ "libgazebo_ros_skid_steer_drive.so", "libgazebo_ros_diff_drive.so" };
-        importerHook.m_supportedPluginParams = AZStd::unordered_set<AZStd::string>{
-            ">wheelSeparation",        ">wheelDiameter",   ">wheelAcceleration", ">leftJoint",      ">rightJoint",       ">wheelDiameter",
-            ">leftFrontJoint",         ">rightFrontJoint", ">leftRearJoint",     ">rightRearJoint", ">wheel_separation", ">wheel_diameter",
-            ">max_wheel_acceleration", ">num_wheel_pairs", ">left_joint",        ">right_joint"
-        };
+        importerHook.m_supportedPluginParams =
+            AZStd::unordered_set<AZStd::string>{ ">wheelSeparation", ">wheelDiameter",    ">leftJoint",       ">rightJoint",
+                                                 ">wheelDiameter",   ">leftFrontJoint",   ">rightFrontJoint", ">leftRearJoint",
+                                                 ">rightRearJoint",  ">wheel_separation", ">wheel_diameter",  ">num_wheel_pairs",
+                                                 ">left_joint",      ">right_joint" };
 
         importerHook.m_sdfPluginToComponentCallback =
             [](AZ::Entity& entity, const sdf::Plugin& sdfPlugin, const sdf::Model& sdfModel, const CreatedEntitiesMap& createdEntities)
@@ -188,18 +187,31 @@ namespace ROS2RobotImporter::SDFormat
         {
             // Parse parameters
             const sdf::ElementPtr element = sdfPlugin.Element();
-            VehicleDynamics::VehicleConfiguration vehicleConfiguration =
-                SkidSteeringParser::CreateVehicleConfiguration(element, sdfModel, createdEntities);
-            VehicleDynamics::SkidSteeringModelLimits modelLimits = SkidSteeringParser::CreateModelLimits(element);
+            const auto vehicleConfiguration = SkidSteeringParser::CreateVehicleConfiguration(element, sdfModel, createdEntities);
+            ROS2Controllers::ControlConfiguration controlConfiguration;
+            controlConfiguration.m_steering = ROS2Controllers::ControlConfiguration::Steering::Twist;
+
+            // libgazebo_ros_diff_drive plugin does not implement all parameters, use O3DE defaults:
+            constexpr float linearLimit = 2.0f;
+            constexpr float angularLimit = 3.5f;
+            constexpr float linearAcceleration = 3.5f;
+            constexpr float angularAcceleration = 2.0f;
 
             // Create required components
+            auto* interface = ROS2Controllers::ROS2ControllersEditorInterface::Get();
+            AZ_Assert(interface, "ROS2ControllersEditorInterface not available in ROS2SkidSteeringModelPluginHook");
+            if (!interface)
+            {
+                return AZ::Failure(AZStd::string("ROS2ControllersInterface is not available. Cannot create components."));
+            }
+
             HooksUtils::CreateComponent<ROS2::ROS2FrameEditorComponent>(entity);
-            HooksUtils::CreateComponent<ROS2Controllers::ROS2RobotControlComponent>(entity);
-            HooksUtils::CreateComponent<ROS2Controllers::VehicleDynamics::SkidSteeringModelComponent>(
-                entity, vehicleConfiguration, VehicleDynamics::SkidSteeringDriveModel(modelLimits));
+            interface->CreateROS2RobotControlComponent(entity, controlConfiguration);
+            interface->CreateSkidSteeringModelComponent(
+                entity, vehicleConfiguration, linearLimit, angularLimit, linearAcceleration, angularAcceleration);
 
             // Create Skid Steering Control Component
-            if (HooksUtils::CreateComponent<ROS2Controllers::SkidSteeringControlComponent>(entity))
+            if (interface->CreateSkidSteeringControlComponent(entity))
             {
                 return AZ::Success();
             }

+ 8 - 10
Gems/ROS2RobotImporter/Code/Source/RobotImporter/SDFormat/ROS2ModelPluginHooks.h

@@ -12,18 +12,16 @@
 
 namespace ROS2RobotImporter::SDFormat::ROS2ModelPluginHooks
 {
-    // temporarily disable import hooks for sensors and models for https://github.com/o3de/sig-simulation/pull/96
+    //! Get a mapping of SDFormat ackermann_drive plugin into O3DE components.
+    ModelPluginImporterHook ROS2AckermannModel();
 
-    // //! Get a mapping of SDFormat skid_steer_drive and diff_drive plugins into O3DE components.
-    // ModelPluginImporterHook ROS2SkidSteeringModel();
+    //! Get a mapping of SDFormat skid_steer_drive and diff_drive plugins into O3DE components.
+    ModelPluginImporterHook ROS2SkidSteeringModel();
 
-    // //! Get a mapping of SDFormat ackermann_drive plugin into O3DE components.
-    // ModelPluginImporterHook ROS2AckermannModel();
+    //! Get a mapping of SDFormat joint_pose_trajectory plugin into O3DE components.
+    ModelPluginImporterHook ROS2JointPoseTrajectoryModel();
 
-    // //! Get a mapping of SDFormat joint_state_publisher plugin into O3DE components.
-    // ModelPluginImporterHook ROS2JointStatePublisherModel();
-
-    //  //! Get a mapping of SDFormat joint_pose_trajectory plugin into O3DE components.
-    // ModelPluginImporterHook ROS2JointPoseTrajectoryModel();
+    //! Get a mapping of SDFormat joint_state_publisher plugin into O3DE components.
+    ModelPluginImporterHook ROS2JointStatePublisherModel();
 
 } // namespace ROS2RobotImporter::SDFormat::ROS2ModelPluginHooks

+ 4 - 5
Gems/ROS2RobotImporter/Code/Source/Tools/ROS2RobotImporterEditorSystemComponent.cpp

@@ -67,15 +67,14 @@ namespace ROS2RobotImporter
         RobotImporterRequestBus::Handler::BusConnect();
 
         // Register default sensor and plugin hooks
-        // temporarily disable import hooks for sensors and models for https://github.com/o3de/sig-simulation/pull/96
         m_sensorHooks.emplace_back(SDFormat::ROS2SensorHooks::ROS2CameraSensor());
         m_sensorHooks.emplace_back(SDFormat::ROS2SensorHooks::ROS2GNSSSensor());
         m_sensorHooks.emplace_back(SDFormat::ROS2SensorHooks::ROS2ImuSensor());
         m_sensorHooks.emplace_back(SDFormat::ROS2SensorHooks::ROS2LidarSensor());
-        // m_modelPluginHooks.emplace_back(SDFormat::ROS2ModelPluginHooks::ROS2AckermannModel());
-        // m_modelPluginHooks.emplace_back(SDFormat::ROS2ModelPluginHooks::ROS2SkidSteeringModel());
-        // m_modelPluginHooks.emplace_back(SDFormat::ROS2ModelPluginHooks::ROS2JointStatePublisherModel());
-        // m_modelPluginHooks.emplace_back(SDFormat::ROS2ModelPluginHooks::ROS2JointPoseTrajectoryModel());
+        m_modelPluginHooks.emplace_back(SDFormat::ROS2ModelPluginHooks::ROS2AckermannModel());
+        m_modelPluginHooks.emplace_back(SDFormat::ROS2ModelPluginHooks::ROS2SkidSteeringModel());
+        m_modelPluginHooks.emplace_back(SDFormat::ROS2ModelPluginHooks::ROS2JointPoseTrajectoryModel());
+        m_modelPluginHooks.emplace_back(SDFormat::ROS2ModelPluginHooks::ROS2JointStatePublisherModel());
 
         // Query user-defined sensor and plugin hooks
         auto serializeContext = AZ::Interface<AZ::ComponentApplicationRequests>::Get()->GetSerializeContext();

+ 63 - 60
Gems/ROS2RobotImporter/Code/Tests/SdfParserTest.cpp

@@ -610,65 +610,68 @@ namespace UnitTest
         EXPECT_EQ(unsupportedLaserParams[0U], "plugin \"librayplugin.so\"");
     }
 
-    // temporarily disable import hooks for sensors and models for https://github.com/o3de/sig-simulation/pull/96
-    // TEST_F(SdfParserTest, SensorPluginImporterHookCheck)
-    // {
-    //     {
-    //         const auto xmlStr = GetSdfWithTwoSensors();
-    //         const auto sdfRootOutcome = UrdfParser::Parse(xmlStr, {});
-    //         ASSERT_TRUE(sdfRootOutcome);
-    //         const auto& sdfRoot = sdfRootOutcome.GetRoot();
-    //         const auto* sdfModel = sdfRoot.Model();
-    //         ASSERT_NE(nullptr, sdfModel);
-    //         const sdf::ElementPtr cameraElement = sdfModel->LinkByName("link1")->SensorByIndex(0U)->Element();
-    //         const auto& cameraImporterHook = SDFormat::ROS2SensorHooks::ROS2CameraSensor();
-
-    //         const auto& unsupportedCameraParams = Utils::SDFormat::GetUnsupportedParams(
-    //             cameraElement, cameraImporterHook.m_supportedSensorParams, cameraImporterHook.m_pluginNames,
-    //             cameraImporterHook.m_supportedPluginParams);
-    //         EXPECT_EQ(unsupportedCameraParams.size(), 1U);
-    //         EXPECT_EQ(unsupportedCameraParams[0U], "plugin \"libgazebo_ros_camera.so\": >camera_name");
-
-    //         sdf::Plugin plug;
-    //         plug.SetName("test_camera");
-    //         plug.SetFilename("libgazebo_ros_camera.so");
-    //         EXPECT_TRUE(Utils::SDFormat::IsPluginSupported(plug, cameraImporterHook.m_pluginNames));
-    //         plug.SetFilename("/usr/lib/libgazebo_ros_openni_kinect.so");
-    //         EXPECT_TRUE(Utils::SDFormat::IsPluginSupported(plug, cameraImporterHook.m_pluginNames));
-    //         plug.SetFilename("~/dev/libgazebo_ros_imu.so");
-    //         EXPECT_FALSE(Utils::SDFormat::IsPluginSupported(plug, cameraImporterHook.m_pluginNames));
-    //         plug.SetFilename("libgazebo_ros_camera");
-    //         EXPECT_FALSE(Utils::SDFormat::IsPluginSupported(plug, cameraImporterHook.m_pluginNames));
-
-    //         EXPECT_TRUE(cameraImporterHook.m_sensorTypes.contains(sdf::SensorType::CAMERA));
-    //         EXPECT_TRUE(cameraImporterHook.m_sensorTypes.contains(sdf::SensorType::DEPTH_CAMERA));
-    //         EXPECT_FALSE(cameraImporterHook.m_sensorTypes.contains(sdf::SensorType::GPS));
-
-    //         const sdf::ElementPtr lidarElement = sdfModel->LinkByName("link2")->SensorByIndex(0U)->Element();
-    //         const auto& lidarImporterHook = SDFormat::ROS2SensorHooks::ROS2LidarSensor();
-    //         const auto& unsupportedLidarParams = Utils::SDFormat::GetUnsupportedParams(
-    //             lidarElement, lidarImporterHook.m_supportedSensorParams, lidarImporterHook.m_pluginNames,
-    //             lidarImporterHook.m_supportedPluginParams);
-    //         EXPECT_EQ(unsupportedLidarParams.size(), 3U);
-    //         EXPECT_EQ(unsupportedLidarParams[0U], ">always_on");
-    //         EXPECT_EQ(unsupportedLidarParams[1U], ">ray>range>resolution");
-    //         EXPECT_EQ(unsupportedLidarParams[2U], "plugin \"librayplugin.so\"");
-    //     }
-    //     {
-    //         const auto xmlStr = GetSdfWithImuSensor();
-    //         const auto sdfRootOutcome = UrdfParser::Parse(xmlStr, {});
-    //         ASSERT_TRUE(sdfRootOutcome);
-    //         const auto& sdfRoot = sdfRootOutcome.GetRoot();
-    //         const auto* sdfModel = sdfRoot.Model();
-    //         ASSERT_NE(nullptr, sdfModel);
-    //         const sdf::ElementPtr imuElement = sdfModel->LinkByName("link1")->SensorByIndex(0U)->Element();
-    //         const auto& importerHook = SDFormat::ROS2SensorHooks::ROS2ImuSensor();
-
-    //         const auto& unsupportedImuParams = Utils::SDFormat::GetUnsupportedParams(
-    //               imuElement, importerHook.m_supportedSensorParams, importerHook.m_pluginNames, importerHook.m_supportedPluginParams);
-    //         EXPECT_EQ(unsupportedImuParams.size(), 1U);
-    //         EXPECT_EQ(unsupportedImuParams[0U], ">always_on");
-    //     }
-    // }
+    TEST_F(SdfParserTest, SensorPluginImporterHookCheck)
+    {
+        {
+            const auto xmlStr = GetSdfWithTwoSensors();
+            const auto sdfRootOutcome = UrdfParser::Parse(xmlStr, {});
+            ASSERT_TRUE(sdfRootOutcome);
+            const auto& sdfRoot = sdfRootOutcome.GetRoot();
+            const auto* sdfModel = sdfRoot.Model();
+            ASSERT_NE(nullptr, sdfModel);
+            const sdf::ElementPtr cameraElement = sdfModel->LinkByName("link1")->SensorByIndex(0U)->Element();
+            const auto& cameraImporterHook = SDFormat::ROS2SensorHooks::ROS2CameraSensor();
+
+            const auto& unsupportedCameraParams = Utils::SDFormat::GetUnsupportedParams(
+                cameraElement,
+                cameraImporterHook.m_supportedSensorParams,
+                cameraImporterHook.m_pluginNames,
+                cameraImporterHook.m_supportedPluginParams);
+            EXPECT_EQ(unsupportedCameraParams.size(), 1U);
+            EXPECT_EQ(unsupportedCameraParams[0U], "plugin \"libgazebo_ros_camera.so\": >camera_name");
+
+            sdf::Plugin plug;
+            plug.SetName("test_camera");
+            plug.SetFilename("libgazebo_ros_camera.so");
+            EXPECT_TRUE(Utils::SDFormat::IsPluginSupported(plug, cameraImporterHook.m_pluginNames));
+            plug.SetFilename("/usr/lib/libgazebo_ros_openni_kinect.so");
+            EXPECT_TRUE(Utils::SDFormat::IsPluginSupported(plug, cameraImporterHook.m_pluginNames));
+            plug.SetFilename("~/dev/libgazebo_ros_imu.so");
+            EXPECT_FALSE(Utils::SDFormat::IsPluginSupported(plug, cameraImporterHook.m_pluginNames));
+            plug.SetFilename("libgazebo_ros_camera");
+            EXPECT_FALSE(Utils::SDFormat::IsPluginSupported(plug, cameraImporterHook.m_pluginNames));
+
+            EXPECT_TRUE(cameraImporterHook.m_sensorTypes.contains(sdf::SensorType::CAMERA));
+            EXPECT_TRUE(cameraImporterHook.m_sensorTypes.contains(sdf::SensorType::DEPTH_CAMERA));
+            EXPECT_FALSE(cameraImporterHook.m_sensorTypes.contains(sdf::SensorType::GPS));
+
+            const sdf::ElementPtr lidarElement = sdfModel->LinkByName("link2")->SensorByIndex(0U)->Element();
+            const auto& lidarImporterHook = SDFormat::ROS2SensorHooks::ROS2LidarSensor();
+            const auto& unsupportedLidarParams = Utils::SDFormat::GetUnsupportedParams(
+                lidarElement,
+                lidarImporterHook.m_supportedSensorParams,
+                lidarImporterHook.m_pluginNames,
+                lidarImporterHook.m_supportedPluginParams);
+            EXPECT_EQ(unsupportedLidarParams.size(), 3U);
+            EXPECT_EQ(unsupportedLidarParams[0U], ">always_on");
+            EXPECT_EQ(unsupportedLidarParams[1U], ">ray>range>resolution");
+            EXPECT_EQ(unsupportedLidarParams[2U], "plugin \"librayplugin.so\"");
+        }
+        {
+            const auto xmlStr = GetSdfWithImuSensor();
+            const auto sdfRootOutcome = UrdfParser::Parse(xmlStr, {});
+            ASSERT_TRUE(sdfRootOutcome);
+            const auto& sdfRoot = sdfRootOutcome.GetRoot();
+            const auto* sdfModel = sdfRoot.Model();
+            ASSERT_NE(nullptr, sdfModel);
+            const sdf::ElementPtr imuElement = sdfModel->LinkByName("link1")->SensorByIndex(0U)->Element();
+            const auto& importerHook = SDFormat::ROS2SensorHooks::ROS2ImuSensor();
+
+            const auto& unsupportedImuParams = Utils::SDFormat::GetUnsupportedParams(
+                imuElement, importerHook.m_supportedSensorParams, importerHook.m_pluginNames, importerHook.m_supportedPluginParams);
+            EXPECT_EQ(unsupportedImuParams.size(), 1U);
+            EXPECT_EQ(unsupportedImuParams[0U], ">always_on");
+        }
+    }
 
 } // namespace UnitTest

+ 4 - 5
Gems/ROS2RobotImporter/Code/ros2robotimporter_editor_private_files.cmake

@@ -29,15 +29,14 @@ set(FILES
     Source/RobotImporter/Pages/XacroParamsPage.h
     Source/RobotImporter/RobotImporterWidget.cpp
     Source/RobotImporter/RobotImporterWidget.h
-    # temporarily disable import hooks for sensors and models for https://github.com/o3de/sig-simulation/pull/96
-    # Source/RobotImporter/SDFormat/Hooks/ROS2AckermannModelHook.cpp
+    Source/RobotImporter/SDFormat/Hooks/ROS2AckermannModelHook.cpp
     Source/RobotImporter/SDFormat/Hooks/ROS2CameraSensorHook.cpp
     Source/RobotImporter/SDFormat/Hooks/ROS2GNSSSensorHook.cpp
     Source/RobotImporter/SDFormat/Hooks/ROS2ImuSensorHook.cpp
+    Source/RobotImporter/SDFormat/Hooks/ROS2JointPoseTrajectoryModelHook.cpp
+    Source/RobotImporter/SDFormat/Hooks/ROS2JointStatePublisherModelHook.cpp
     Source/RobotImporter/SDFormat/Hooks/ROS2LidarSensorHook.cpp
-    # Source/RobotImporter/SDFormat/Hooks/ROS2SkidSteeringModelHook.cpp
-    # Source/RobotImporter/SDFormat/Hooks/ROS2JointPoseTrajectoryModelHook.cpp
-    # Source/RobotImporter/SDFormat/Hooks/ROS2JointStatePublisherModelHook.cpp
+    Source/RobotImporter/SDFormat/Hooks/ROS2SkidSteeringModelHook.cpp
     Source/RobotImporter/SDFormat/ROS2ModelPluginHooks.h
     Source/RobotImporter/SDFormat/ROS2SDFormatHooksUtils.cpp
     Source/RobotImporter/SDFormat/ROS2SDFormatHooksUtils.h

+ 2 - 1
Gems/ROS2RobotImporter/gem.json

@@ -21,7 +21,8 @@
     "requirements": "Requires ROS 2 Gem, ROS2Sensors Gem and ROS2Controllers Gem.",
     "documentation_url": "Link to any documentation of your Gem",
     "dependencies": [
-        "ROS2>=3.3.0",
+        "ROS2>=4.0.0",
+        "ROS2Controllers",
         "ROS2Sensors"
     ],
     "repo_uri": "https://github.com/o3de/o3de-extras/",

+ 2 - 1
Gems/ROS2Sensors/Code/Source/Tools/ROS2SensorsEditorSystemComponent.cpp

@@ -25,7 +25,8 @@ namespace ROS2Sensors
     {
         if (auto serializeContext = azrtti_cast<AZ::SerializeContext*>(context))
         {
-            serializeContext->Class<ROS2SensorsEditorSystemComponent, ROS2SensorsSystemComponent>()->Version(0);
+            serializeContext->Class<ROS2SensorsEditorSystemComponent, ROS2SensorsSystemComponent>()->Version(1)->Attribute(
+                AZ::Edit::Attributes::SystemComponentTags, AZStd::vector<AZ::Crc32>({ AZ_CRC_CE("AssetBuilder") }));
         }
     }
 

+ 1 - 1
Gems/ROS2Sensors/gem.json

@@ -23,7 +23,7 @@
     "dependencies": [
         "LevelGeoreferencing",
         "PhysX5",
-        "ROS2>=3.3.0"
+        "ROS2>=4.0.0"
     ],
     "repo_uri": "https://github.com/o3de/o3de-extras/",
     "source_control_uri": "https://github.com/o3de/o3de-extras/development/Gems/ROS2Sensors",