Pārlūkot izejas kodu

API modifications and cleanup (#332)

* API modifications and cleanup
- Moved some classes that are useful for development of robotic projects to API.
- Cleaned up MotorizedJoint documentation, naming.
- Renamed MotorizedJoint to MotorizedJointComponent

Signed-off-by: Adam Dąbrowski <[email protected]>
Adam Dąbrowski 2 gadi atpakaļ
vecāks
revīzija
727a8147e4
33 mainītis faili ar 181 papildinājumiem un 213 dzēšanām
  1. 1 1
      Gems/ROS2/Code/Include/ROS2/Communication/TopicConfiguration.h
  2. 0 129
      Gems/ROS2/Code/Include/ROS2/Manipulator/MotorizedJoint.h
  3. 92 0
      Gems/ROS2/Code/Include/ROS2/Manipulator/MotorizedJointComponent.h
  4. 0 0
      Gems/ROS2/Code/Include/ROS2/RobotControl/Ackermann/AckermannBus.h
  5. 0 0
      Gems/ROS2/Code/Include/ROS2/RobotControl/Ackermann/AckermannCommandStruct.h
  6. 0 0
      Gems/ROS2/Code/Include/ROS2/RobotControl/ControlConfiguration.h
  7. 0 0
      Gems/ROS2/Code/Include/ROS2/RobotControl/ControlSubscriptionHandler.h
  8. 0 0
      Gems/ROS2/Code/Include/ROS2/RobotControl/Twist/TwistBus.h
  9. 0 0
      Gems/ROS2/Code/Include/ROS2/Sensor/ROS2SensorComponent.h
  10. 0 0
      Gems/ROS2/Code/Include/ROS2/Sensor/SensorConfiguration.h
  11. 0 0
      Gems/ROS2/Code/Include/ROS2/Spawner/SpawnerBus.h
  12. 1 1
      Gems/ROS2/Code/Source/Camera/ROS2CameraSensorComponent.h
  13. 1 1
      Gems/ROS2/Code/Source/GNSS/ROS2GNSSSensorComponent.h
  14. 1 1
      Gems/ROS2/Code/Source/Imu/ROS2ImuSensorComponent.h
  15. 1 1
      Gems/ROS2/Code/Source/Lidar/ROS2LidarSensorComponent.h
  16. 58 48
      Gems/ROS2/Code/Source/Manipulator/MotorizedJointComponent.cpp
  17. 1 1
      Gems/ROS2/Code/Source/Odometry/ROS2OdometrySensorComponent.h
  18. 2 2
      Gems/ROS2/Code/Source/ROS2ModuleInterface.h
  19. 2 2
      Gems/ROS2/Code/Source/RobotControl/Ackermann/AckermannSubscriptionHandler.cpp
  20. 1 1
      Gems/ROS2/Code/Source/RobotControl/Ackermann/AckermannSubscriptionHandler.h
  21. 1 1
      Gems/ROS2/Code/Source/RobotControl/ControlConfiguration.cpp
  22. 1 1
      Gems/ROS2/Code/Source/RobotControl/Controllers/AckermannController/AckermannControlComponent.h
  23. 1 1
      Gems/ROS2/Code/Source/RobotControl/Controllers/RigidBodyController/RigidBodyTwistControlComponent.h
  24. 2 2
      Gems/ROS2/Code/Source/RobotControl/ROS2RobotControlComponent.cpp
  25. 2 2
      Gems/ROS2/Code/Source/RobotControl/ROS2RobotControlComponent.h
  26. 1 1
      Gems/ROS2/Code/Source/RobotControl/Twist/TwistSubscriptionHandler.cpp
  27. 1 1
      Gems/ROS2/Code/Source/RobotControl/Twist/TwistSubscriptionHandler.h
  28. 1 2
      Gems/ROS2/Code/Source/RobotImporter/URDF/URDFPrefabMaker.cpp
  29. 1 1
      Gems/ROS2/Code/Source/Sensor/ROS2SensorComponent.cpp
  30. 1 1
      Gems/ROS2/Code/Source/Sensor/SensorConfiguration.cpp
  31. 1 1
      Gems/ROS2/Code/Source/Spawner/ROS2SpawnerComponent.h
  32. 1 10
      Gems/ROS2/Code/ros2_files.cmake
  33. 6 1
      Gems/ROS2/Code/ros2_header_files.cmake

+ 1 - 1
Gems/ROS2/Code/Include/ROS2/Communication/TopicConfiguration.h

@@ -14,7 +14,7 @@
 
 namespace ROS2
 {
-    //! A structure for a single ROS2 publisher configuration.
+    //! A structure for a single ROS2 topic, a part of publisher or subscriber configuration.
     struct TopicConfiguration
     {
     public:

+ 0 - 129
Gems/ROS2/Code/Include/ROS2/Manipulator/MotorizedJoint.h

@@ -1,129 +0,0 @@
-/*
- * 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/VehicleDynamics/DriveModels/PidConfiguration.h"
-#include <AzCore/Component/Component.h>
-#include <AzCore/Component/TickBus.h>
-#include <AzCore/Math/Transform.h>
-#include <AzCore/Math/Vector2.h>
-
-namespace ROS2
-{
-    //! Helper that allows us to design a joint with a 'motor'
-    //! It can affect the scene with two APIS: TransformBus and RigidBodyBus
-    //! TransformBus mode, called `AnimationMode` changes local transform. In this mode, you cannot have a rigid body
-    //! controller enabled. It is intended to use in a simple scenario.
-    //! With RigidBodyBus it applies forces and torque according to PID control.
-    //! @note This class is already used through ROS2FrameComponent.
-    // TODO Add interface using EBus, test implement also rotation, add ramps, cascading controllers,
-    // TODO automatic tests on test scene
-
-    class MotorizedJoint
-        : public AZ::Component
-        , public AZ::TickBus::Handler
-    {
-    public:
-        AZ_COMPONENT(MotorizedJoint, "{AE9207DB-5B7E-4F70-A7DD-C4EAD8DD9403}", AZ::Component);
-
-        // AZ::Component interface implementation.
-        MotorizedJoint() = default;
-        ~MotorizedJoint() = default;
-        void Activate() override;
-        void Deactivate() override;
-        static void Reflect(AZ::ReflectContext* context);
-
-        //! Set a setpoint (e.g. desired local position). Controller follows it.
-        void SetSetpoint(float setpoint);
-
-        //! Get current control error. It is a difference between control value and measurement
-        //! For steady state should be close to zero
-        //! @returns error in meters for linear joints and radians for angular
-        float GetError() const;
-
-        //! Get current position from measurement.
-        //! For steady state should be close to setpoint
-        //! @returns current position  in meters for linear joints and radians for angular
-        float GetCurrentPosition() const;
-
-        //! Get a degree of freedom direction.
-        AZ::Vector3 GetDir() const
-        {
-            return m_jointDir;
-        };
-
-    private:
-        float ComputeMeasurement(AZ::ScriptTimePoint time);
-
-        void SetVelocity(float velocity, float deltaTime);
-
-        // TODO apply RotVel...
-        void ApplyLinVelAnimation(float velocity, float deltaTime);
-
-        void ApplyLinVelRigidBodyImpulse(float velocity, float deltaTime);
-
-        void ApplyLinVelRigidBody(float velocity, float deltaTime);
-
-        void OnTick(float deltaTime, AZ::ScriptTimePoint time) override;
-
-        ///! Direction of degree of freedom
-        AZ::Vector3 m_jointDir{ 0.f, 0.f, 1.f };
-
-        ///! Direction of degree of freedom
-        AZ::Vector3 m_effortAxis{ 0.f, 0.f, 1.f };
-
-        ///! Limits - on limit controller will apply force only in opposite direction
-        AZStd::pair<float, float> m_limits{ -0.5f, 0.5f };
-
-        ///! PID controller for position
-        VehicleDynamics::PidConfiguration m_pidPos;
-
-        ///! offset added to setpoint
-        float m_zeroOffset{ 0.f };
-
-        ///! Linear mode - apply force
-        bool m_linear{ true };
-
-        ///! Use TransformBus instead of RigidBodyBus
-        bool m_animationMode{ true };
-
-        ///! Enable sinusoidal signal generator to setpoint (for tuning)
-        bool m_testSinusoidal{ true };
-
-        ///! Print To console debug info
-        bool m_debugPrint{ false };
-
-        ///! Amplitude of test signal generator
-        float m_sinAmplitude{ 0.5 };
-
-        ///! DC of test signal generator
-        float m_sinDC{ 0.25 };
-
-        ///! Frequency of test signal generator
-        float m_sinFreq{ 0.1 };
-
-        ///! Last measured position
-        float m_currentPosition{ 0 };
-
-        ///! Last measured position
-        float m_currentVelocity{ 0 };
-
-        float m_setpoint{ 0 };
-        float m_error{ 0 };
-        double m_lastMeasurementTime;
-
-        ///! Optional Entity that allows to visualize desired setpoint value
-        AZ::EntityId m_debugDrawEntity;
-
-        ///! initial transform of m_debugDrawEntity. It will be modified by the desired setpoint value in the set direction.
-        AZ::Transform m_debugDrawEntityInitialTransform;
-
-        ///! Overide parent entity
-        AZ::EntityId m_ParentOverride;
-    };
-} // namespace ROS2

+ 92 - 0
Gems/ROS2/Code/Include/ROS2/Manipulator/MotorizedJointComponent.h

@@ -0,0 +1,92 @@
+/*
+ * 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/VehicleDynamics/DriveModels/PidConfiguration.h"
+#include <AzCore/Component/Component.h>
+#include <AzCore/Component/TickBus.h>
+#include <AzCore/Math/Transform.h>
+#include <AzCore/Math/Vector2.h>
+
+namespace ROS2
+{
+    //! A prototype component for simulated joint with a motor.
+    //! It works with either TransformBus or RigidBodyBus.
+    //! TransformBus mode, called `AnimationMode` changes local transform. In this mode, you cannot have a rigid body
+    //! controller enabled. With RigidBodyBus it applies forces and torque according to PID control.
+    //! @note This class is already used through ROS2FrameComponent.
+    // TODO This is a prototype. Tasks: refactor, add bus interface, rotation, ramps, cascading controllers, tests.
+    class MotorizedJointComponent
+        : public AZ::Component
+        , public AZ::TickBus::Handler
+    {
+    public:
+        AZ_COMPONENT(MotorizedJointComponent, "{AE9207DB-5B7E-4F70-A7DD-C4EAD8DD9403}", AZ::Component);
+
+        MotorizedJointComponent() = default;
+        ~MotorizedJointComponent() = default;
+        void Activate() override;
+        void Deactivate() override;
+        static void Reflect(AZ::ReflectContext* context);
+
+        //! Set a setpoint (e.g. desired local position). The controller will follow it.
+        void SetSetpoint(float setpoint);
+
+        //! Get current control error. It is the difference between control value and measurement.
+        //! When the setpoint is reached this should be close to zero.
+        //! @returns control error, in meters for linear joints and in radians for angular joints.
+        float GetError() const;
+
+        //! Get current position from measurement.
+        //! @returns current position, in meters for linear joints and radians for angular joints.
+        float GetCurrentPosition() const;
+
+        //! Get a degree of freedom direction.
+        //! @returns direction of joint movement in global coordinates.
+        AZ::Vector3 GetDir() const
+        {
+            return m_jointDir;
+        };
+
+    private:
+        float ComputeMeasurement(AZ::ScriptTimePoint time);
+        void SetVelocity(float velocity, float deltaTime);
+        void ApplyLinVelAnimation(float velocity, float deltaTime);
+        void ApplyLinVelRigidBodyImpulse(float velocity, float deltaTime);
+        void ApplyLinVelRigidBody(float velocity, float deltaTime);
+        void OnTick(float deltaTime, AZ::ScriptTimePoint time) override;
+
+        AZ::Vector3 m_jointDir{ 0.f, 0.f, 1.f }; //!< Direction of joint movement in parent frame of reference, used to compute measurement.
+        AZ::Vector3 m_effortAxis{ 0.f, 0.f, 1.f }; //!< Direction of force or torque application in owning entity frame of reference.
+        AZStd::pair<float, float> m_limits{ -0.5f, 0.5f }; //!< limits of joint, the force is applied only when joint is within limits.
+        VehicleDynamics::PidConfiguration m_pidPos; //!< PID controller for position.
+
+        bool m_linear{ true }; //!< Linear mode. The force is applied through RigidBodyBus.
+        bool m_animationMode{ true }; //!< Use TransformBus (animation mode, no physics) instead of RigidBodyBus.
+
+        // TODO - remove test signal?
+        bool m_testSinusoidal{ true }; //!< Enable sinusoidal signal generator to setpoint (for tuning).
+        float m_sinAmplitude{ 0.5 }; //!< Amplitude of test signal generator.
+        float m_sinDC{ 0.25 }; //!< DC of test signal generator.
+        float m_sinFreq{ 0.1 }; //!< Frequency of test signal generator.
+
+        float m_zeroOffset{ 0.f }; //!< offset added to setpoint.
+        float m_setpoint{ 0 }; //!< Desired local position.
+        float m_error{ 0 }; //!< Current error (difference between control value and measurement).
+        float m_currentPosition{ 0 }; //!< Last measured position.
+        float m_currentVelocity{ 0 }; //!< Last measured velocity.
+        double m_lastMeasurementTime; //!< Last measurement time in seconds.
+
+        // TODO - remove/replace with proper API use (EntityDebugDisplayEventBus)
+        AZ::EntityId m_debugDrawEntity; //!< Optional Entity that allows to visualize desired setpoint value.
+        AZ::Transform m_debugDrawEntityInitialTransform; //!< Initial transform of m_debugDrawEntity.
+        bool m_debugPrint{ false }; //!< Print debug info to the console.
+
+        AZ::EntityId m_measurementReferenceEntity; //!< Entity used for reference for measurements. Defaults to parent entity.
+    };
+} // namespace ROS2

+ 0 - 0
Gems/ROS2/Code/Source/RobotControl/Ackermann/AckermannBus.h → Gems/ROS2/Code/Include/ROS2/RobotControl/Ackermann/AckermannBus.h


+ 0 - 0
Gems/ROS2/Code/Source/RobotControl/Ackermann/AckermannCommandStruct.h → Gems/ROS2/Code/Include/ROS2/RobotControl/Ackermann/AckermannCommandStruct.h


+ 0 - 0
Gems/ROS2/Code/Source/RobotControl/ControlConfiguration.h → Gems/ROS2/Code/Include/ROS2/RobotControl/ControlConfiguration.h


+ 0 - 0
Gems/ROS2/Code/Source/RobotControl/ControlSubscriptionHandler.h → Gems/ROS2/Code/Include/ROS2/RobotControl/ControlSubscriptionHandler.h


+ 0 - 0
Gems/ROS2/Code/Source/RobotControl/Twist/TwistBus.h → Gems/ROS2/Code/Include/ROS2/RobotControl/Twist/TwistBus.h


+ 0 - 0
Gems/ROS2/Code/Source/Sensor/ROS2SensorComponent.h → Gems/ROS2/Code/Include/ROS2/Sensor/ROS2SensorComponent.h


+ 0 - 0
Gems/ROS2/Code/Source/Sensor/SensorConfiguration.h → Gems/ROS2/Code/Include/ROS2/Sensor/SensorConfiguration.h


+ 0 - 0
Gems/ROS2/Code/Source/Spawner/SpawnerBus.h → Gems/ROS2/Code/Include/ROS2/Spawner/SpawnerBus.h


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

@@ -11,7 +11,7 @@
 #include <sensor_msgs/msg/camera_info.hpp>
 #include <sensor_msgs/msg/image.hpp>
 
-#include "Sensor/ROS2SensorComponent.h"
+#include "ROS2/Sensor/ROS2SensorComponent.h"
 
 #include <AzCore/Component/Component.h>
 

+ 1 - 1
Gems/ROS2/Code/Source/GNSS/ROS2GNSSSensorComponent.h

@@ -7,7 +7,7 @@
  */
 #pragma once
 
-#include "Sensor/ROS2SensorComponent.h"
+#include "ROS2/Sensor/ROS2SensorComponent.h"
 #include <AzCore/Math/Transform.h>
 #include <AzCore/Serialization/SerializeContext.h>
 #include <rclcpp/publisher.hpp>

+ 1 - 1
Gems/ROS2/Code/Source/Imu/ROS2ImuSensorComponent.h

@@ -7,7 +7,7 @@
  */
 #pragma once
 
-#include "Sensor/ROS2SensorComponent.h"
+#include "ROS2/Sensor/ROS2SensorComponent.h"
 #include <AzCore/Math/Transform.h>
 #include <AzCore/Serialization/SerializeContext.h>
 #include <rclcpp/publisher.hpp>

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

@@ -10,7 +10,7 @@
 #include "Lidar/LidarRaycaster.h"
 #include "Lidar/LidarTemplate.h"
 #include "Lidar/LidarTemplateUtils.h"
-#include "Sensor/ROS2SensorComponent.h"
+#include "ROS2/Sensor/ROS2SensorComponent.h"
 #include <Atom/RPI.Public/AuxGeom/AuxGeomDraw.h>
 #include <AzCore/Serialization/SerializeContext.h>
 #include <rclcpp/publisher.hpp>

+ 58 - 48
Gems/ROS2/Code/Source/Manipulator/MotorizedJoint.cpp → Gems/ROS2/Code/Source/Manipulator/MotorizedJointComponent.cpp

@@ -6,7 +6,7 @@
  *
  */
 
-#include "ROS2/Manipulator/MotorizedJoint.h"
+#include "ROS2/Manipulator/MotorizedJointComponent.h"
 #include "AzFramework/Physics/Components/SimulatedBodyComponentBus.h"
 #include <AzCore/Component/Entity.h>
 #include <AzCore/Component/TransformBus.h>
@@ -15,7 +15,7 @@
 
 namespace ROS2
 {
-    void MotorizedJoint::Activate()
+    void MotorizedJointComponent::Activate()
     {
         AZ::TickBus::Handler::BusConnect();
         m_pidPos.InitializePid();
@@ -25,85 +25,95 @@ namespace ROS2
         }
     }
 
-    void MotorizedJoint::Deactivate()
+    void MotorizedJointComponent::Deactivate()
     {
         AZ::TickBus::Handler::BusDisconnect();
     }
 
-    void MotorizedJoint::Reflect(AZ::ReflectContext* context)
+    void MotorizedJointComponent::Reflect(AZ::ReflectContext* context)
     {
         if (AZ::SerializeContext* serialize = azrtti_cast<AZ::SerializeContext*>(context))
         {
-            serialize->Class<MotorizedJoint, AZ::Component>()
+            serialize->Class<MotorizedJointComponent, AZ::Component>()
                 ->Version(2)
-                ->Field("JointAxis", &MotorizedJoint::m_jointDir)
-                ->Field("EffortAxis", &MotorizedJoint::m_effortAxis)
-                ->Field("Limit", &MotorizedJoint::m_limits)
-                ->Field("Linear", &MotorizedJoint::m_linear)
-                ->Field("AnimationMode", &MotorizedJoint::m_animationMode)
-                ->Field("ZeroOffset", &MotorizedJoint::m_zeroOffset)
-                ->Field("PidPosition", &MotorizedJoint::m_pidPos)
-                ->Field("DebugDrawEntity", &MotorizedJoint::m_debugDrawEntity)
-                ->Field("TestSinActive", &MotorizedJoint::m_testSinusoidal)
-                ->Field("TestSinAmplitude", &MotorizedJoint::m_sinAmplitude)
-                ->Field("TestSinFreq", &MotorizedJoint::m_sinFreq)
-                ->Field("TestSinDC", &MotorizedJoint::m_sinDC)
-                ->Field("DebugPrint", &MotorizedJoint::m_debugPrint)
-                ->Field("OverrideParent", &MotorizedJoint::m_ParentOverride);
+                ->Field("JointAxis", &MotorizedJointComponent::m_jointDir)
+                ->Field("EffortAxis", &MotorizedJointComponent::m_effortAxis)
+                ->Field("Limit", &MotorizedJointComponent::m_limits)
+                ->Field("Linear", &MotorizedJointComponent::m_linear)
+                ->Field("AnimationMode", &MotorizedJointComponent::m_animationMode)
+                ->Field("ZeroOffset", &MotorizedJointComponent::m_zeroOffset)
+                ->Field("PidPosition", &MotorizedJointComponent::m_pidPos)
+                ->Field("DebugDrawEntity", &MotorizedJointComponent::m_debugDrawEntity)
+                ->Field("TestSinActive", &MotorizedJointComponent::m_testSinusoidal)
+                ->Field("TestSinAmplitude", &MotorizedJointComponent::m_sinAmplitude)
+                ->Field("TestSinFreq", &MotorizedJointComponent::m_sinFreq)
+                ->Field("TestSinDC", &MotorizedJointComponent::m_sinDC)
+                ->Field("DebugPrint", &MotorizedJointComponent::m_debugPrint)
+                ->Field("OverrideParent", &MotorizedJointComponent::m_measurementReferenceEntity);
 
             if (AZ::EditContext* ec = serialize->GetEditContext())
             {
-                ec->Class<MotorizedJoint>("MotorizedJoint", "MotorizedJoint")
-                    ->ClassElement(AZ::Edit::ClassElements::EditorData, "MotorizedJoint")
+                ec->Class<MotorizedJointComponent>("MotorizedJointComponent", "MotorizedJointComponent")
+                    ->ClassElement(AZ::Edit::ClassElements::EditorData, "MotorizedJointComponent")
                     ->Attribute(AZ::Edit::Attributes::AppearsInAddComponentMenu, AZ_CRC("Game"))
-                    ->Attribute(AZ::Edit::Attributes::Category, "MotorizedJoint")
-                    ->DataElement(AZ::Edit::UIHandlers::Default, &MotorizedJoint::m_jointDir, "Joint Dir.", "Direction of joint.")
-                    ->DataElement(AZ::Edit::UIHandlers::Default, &MotorizedJoint::m_effortAxis, "Effort Dir.", "Direction of joint.")
+                    ->Attribute(AZ::Edit::Attributes::Category, "MotorizedJointComponent")
+                    ->DataElement(AZ::Edit::UIHandlers::Default, &MotorizedJointComponent::m_jointDir, "Joint Dir.", "Direction of joint in parent's reference frame.")
+                    ->DataElement(
+                        AZ::Edit::UIHandlers::Default, &MotorizedJointComponent::m_effortAxis, "Effort Dir.", "Desired direction of force/torque vector that is applied to rigid body.")
 
                     ->DataElement(
                         AZ::Edit::UIHandlers::Default,
-                        &MotorizedJoint::m_limits,
+                        &MotorizedJointComponent::m_limits,
                         "ControllerLimits",
                         "When measurement is outside the limits, ")
                     ->DataElement(
                         AZ::Edit::UIHandlers::Default,
-                        &MotorizedJoint::m_debugDrawEntity,
+                        &MotorizedJointComponent::m_debugDrawEntity,
                         "Setpoint",
                         "Allows to apply debug setpoint visualizer")
                     ->DataElement(
                         AZ::Edit::UIHandlers::Default,
-                        &MotorizedJoint::m_zeroOffset,
+                        &MotorizedJointComponent::m_zeroOffset,
                         "Zero Off.",
                         "Allows to change offset of zero to set point")
                     ->DataElement(
-                        AZ::Edit::UIHandlers::Default, &MotorizedJoint::m_linear, "Linear joint", "Applies linear force instead of torque")
+                        AZ::Edit::UIHandlers::Default,
+                        &MotorizedJointComponent::m_linear,
+                        "Linear joint",
+                        "Applies linear force instead of torque")
                     ->DataElement(
                         AZ::Edit::UIHandlers::Default,
-                        &MotorizedJoint::m_animationMode,
+                        &MotorizedJointComponent::m_animationMode,
                         "Animation mode",
                         "In animation mode, the transform API is used instead of Rigid Body. "
                         "If this property is set to true the Rigid Body Component should be disabled.")
-                    ->DataElement(AZ::Edit::UIHandlers::Default, &MotorizedJoint::m_pidPos, "PidPosition", "PidPosition")
+                    ->DataElement(AZ::Edit::UIHandlers::Default, &MotorizedJointComponent::m_pidPos, "PidPosition", "PidPosition")
                     ->DataElement(
                         AZ::Edit::UIHandlers::Default,
-                        &MotorizedJoint::m_testSinusoidal,
+                        &MotorizedJointComponent::m_testSinusoidal,
                         "SinusoidalTest",
                         "Allows to apply sinusoidal test signal")
                     ->DataElement(
-                        AZ::Edit::UIHandlers::Default, &MotorizedJoint::m_sinAmplitude, "Amplitude", "Amplitude of sinusoidal test signal.")
+                        AZ::Edit::UIHandlers::Default,
+                        &MotorizedJointComponent::m_sinAmplitude,
+                        "Amplitude",
+                        "Amplitude of sinusoidal test signal.")
                     ->DataElement(
-                        AZ::Edit::UIHandlers::Default, &MotorizedJoint::m_sinFreq, "Frequency", "Frequency of sinusoidal test signal.")
-                    ->DataElement(AZ::Edit::UIHandlers::Default, &MotorizedJoint::m_sinDC, "DC", "DC of sinusoidal test signal.")
-                    ->DataElement(AZ::Edit::UIHandlers::Default, &MotorizedJoint::m_debugPrint, "Debug", "Print debug to console")
+                        AZ::Edit::UIHandlers::Default,
+                        &MotorizedJointComponent::m_sinFreq,
+                        "Frequency",
+                        "Frequency of sinusoidal test signal.")
+                    ->DataElement(AZ::Edit::UIHandlers::Default, &MotorizedJointComponent::m_sinDC, "DC", "DC of sinusoidal test signal.")
+                    ->DataElement(AZ::Edit::UIHandlers::Default, &MotorizedJointComponent::m_debugPrint, "Debug", "Print debug to console")
                     ->DataElement(
                         AZ::Edit::UIHandlers::Default,
-                        &MotorizedJoint::m_ParentOverride,
+                        &MotorizedJointComponent::m_measurementReferenceEntity,
                         "Step Parent",
                         "Allows to override a parent to get correct measurement");
             }
         }
     }
-    void MotorizedJoint::OnTick([[maybe_unused]] float deltaTime, [[maybe_unused]] AZ::ScriptTimePoint time)
+    void MotorizedJointComponent::OnTick([[maybe_unused]] float deltaTime, [[maybe_unused]] AZ::ScriptTimePoint time)
     {
         const float measurement = ComputeMeasurement(time);
         if (m_testSinusoidal)
@@ -145,7 +155,7 @@ namespace ROS2
         if (m_debugPrint)
         {
             AZ_Printf(
-                "MotorizedJoint",
+                "MotorizedJointComponent",
                 " %s | pos: %f | err: %f | cntrl : %f | set : %f |",
                 GetEntity()->GetName().c_str(),
                 measurement,
@@ -156,17 +166,17 @@ namespace ROS2
         SetVelocity(speed_control, deltaTime);
     }
 
-    float MotorizedJoint::ComputeMeasurement(AZ::ScriptTimePoint time)
+    float MotorizedJointComponent::ComputeMeasurement(AZ::ScriptTimePoint time)
     {
         AZ::Transform transform;
-        if (!m_ParentOverride.IsValid())
+        if (!m_measurementReferenceEntity.IsValid())
         {
             AZ::TransformBus::EventResult(transform, this->GetEntityId(), &AZ::TransformBus::Events::GetLocalTM);
         }
         else
         {
             AZ::Transform transformStepParent;
-            AZ::TransformBus::EventResult(transformStepParent, m_ParentOverride, &AZ::TransformBus::Events::GetWorldTM);
+            AZ::TransformBus::EventResult(transformStepParent, m_measurementReferenceEntity, &AZ::TransformBus::Events::GetWorldTM);
             AZ::Transform transformStepChild;
             AZ::TransformBus::EventResult(transformStepChild, GetEntityId(), &AZ::TransformBus::Events::GetWorldTM);
             transform = transformStepParent.GetInverse() * transformStepChild;
@@ -187,7 +197,7 @@ namespace ROS2
         return 0;
     }
 
-    void MotorizedJoint::SetVelocity(float velocity, float deltaTime)
+    void MotorizedJointComponent::SetVelocity(float velocity, float deltaTime)
     {
         if (m_animationMode)
         {
@@ -205,7 +215,7 @@ namespace ROS2
         }
     }
 
-    void MotorizedJoint::ApplyLinVelAnimation(float velocity, float deltaTime)
+    void MotorizedJointComponent::ApplyLinVelAnimation(float velocity, float deltaTime)
     {
         AZ::Transform transform;
         AZ::TransformBus::EventResult(transform, this->GetEntityId(), &AZ::TransformBus::Events::GetLocalTM);
@@ -213,7 +223,7 @@ namespace ROS2
         AZ::TransformBus::Event(this->GetEntityId(), &AZ::TransformBus::Events::SetLocalTM, transform);
     }
 
-    void MotorizedJoint::ApplyLinVelRigidBodyImpulse(float velocity, float deltaTime)
+    void MotorizedJointComponent::ApplyLinVelRigidBodyImpulse(float velocity, float deltaTime)
     {
         AZ::Quaternion transform;
         AZ::TransformBus::EventResult(transform, this->GetEntityId(), &AZ::TransformBus::Events::GetWorldRotationQuaternion);
@@ -222,7 +232,7 @@ namespace ROS2
             this->GetEntityId(), &Physics::RigidBodyRequests::ApplyLinearImpulse, force_impulse * deltaTime);
     }
 
-    void MotorizedJoint::ApplyLinVelRigidBody(float velocity, float deltaTime)
+    void MotorizedJointComponent::ApplyLinVelRigidBody(float velocity, float deltaTime)
     {
         AZ::Quaternion transform;
         AZ::TransformBus::EventResult(transform, this->GetEntityId(), &AZ::TransformBus::Events::GetWorldRotationQuaternion);
@@ -233,17 +243,17 @@ namespace ROS2
         Physics::RigidBodyRequestBus::Event(this->GetEntityId(), &Physics::RigidBodyRequests::SetLinearVelocity, new_velocity);
     }
 
-    void MotorizedJoint::SetSetpoint(float setpoint)
+    void MotorizedJointComponent::SetSetpoint(float setpoint)
     {
         m_setpoint = setpoint;
     }
 
-    float MotorizedJoint::GetError() const
+    float MotorizedJointComponent::GetError() const
     {
         return m_error;
     }
 
-    float MotorizedJoint::GetCurrentPosition() const
+    float MotorizedJointComponent::GetCurrentPosition() const
     {
         return m_currentPosition - m_zeroOffset;
     }

+ 1 - 1
Gems/ROS2/Code/Source/Odometry/ROS2OdometrySensorComponent.h

@@ -7,7 +7,7 @@
  */
 #pragma once
 
-#include "Sensor/ROS2SensorComponent.h"
+#include "ROS2/Sensor/ROS2SensorComponent.h"
 #include <AzCore/Math/Transform.h>
 #include <AzCore/Serialization/SerializeContext.h>
 #include <nav_msgs/msg/odometry.hpp>

+ 2 - 2
Gems/ROS2/Code/Source/ROS2ModuleInterface.h

@@ -13,7 +13,7 @@
 #include "Lidar/ROS2LidarSensorComponent.h"
 #include "Odometry/ROS2OdometrySensorComponent.h"
 #include "ROS2/Frame/ROS2FrameComponent.h"
-#include "ROS2/Manipulator/MotorizedJoint.h"
+#include "ROS2/Manipulator/MotorizedJointComponent.h"
 #include "ROS2SystemComponent.h"
 #include "RobotControl/Controllers/AckermannController/AckermannControlComponent.h"
 #include "RobotControl/Controllers/RigidBodyController/RigidBodyTwistControlComponent.h"
@@ -59,7 +59,7 @@ namespace ROS2
                   ROS2SpawnPointComponent::CreateDescriptor(),
                   VehicleDynamics::VehicleModelComponent::CreateDescriptor(),
                   VehicleDynamics::WheelControllerComponent::CreateDescriptor(),
-                  MotorizedJoint::CreateDescriptor() });
+                  MotorizedJointComponent::CreateDescriptor() });
         }
 
         //! Add required SystemComponents to the SystemEntity.

+ 2 - 2
Gems/ROS2/Code/Source/RobotControl/Ackermann/AckermannSubscriptionHandler.cpp

@@ -7,8 +7,8 @@
  */
 
 #include "AckermannSubscriptionHandler.h"
-#include "AckermannBus.h"
-#include "AckermannCommandStruct.h"
+#include "ROS2/RobotControl/Ackermann/AckermannBus.h"
+#include "ROS2/RobotControl/Ackermann/AckermannCommandStruct.h"
 
 namespace ROS2
 {

+ 1 - 1
Gems/ROS2/Code/Source/RobotControl/Ackermann/AckermannSubscriptionHandler.h

@@ -7,7 +7,7 @@
  */
 #pragma once
 
-#include "RobotControl/ControlSubscriptionHandler.h"
+#include "ROS2/RobotControl/ControlSubscriptionHandler.h"
 #include <ackermann_msgs/msg/ackermann_drive.hpp>
 
 namespace ROS2

+ 1 - 1
Gems/ROS2/Code/Source/RobotControl/ControlConfiguration.cpp

@@ -6,7 +6,7 @@
  *
  */
 
-#include "RobotControl/ControlConfiguration.h"
+#include "ROS2/RobotControl/ControlConfiguration.h"
 #include <AzCore/Serialization/EditContext.h>
 
 namespace ROS2

+ 1 - 1
Gems/ROS2/Code/Source/RobotControl/Controllers/AckermannController/AckermannControlComponent.h

@@ -7,7 +7,7 @@
  */
 #pragma once
 
-#include "RobotControl/Ackermann/AckermannBus.h"
+#include "ROS2/RobotControl/Ackermann/AckermannBus.h"
 #include <AzCore/Component/Component.h>
 
 namespace ROS2

+ 1 - 1
Gems/ROS2/Code/Source/RobotControl/Controllers/RigidBodyController/RigidBodyTwistControlComponent.h

@@ -7,7 +7,7 @@
  */
 #pragma once
 
-#include "RobotControl/Twist/TwistBus.h"
+#include "ROS2/RobotControl/Twist/TwistBus.h"
 #include <AzCore/Component/Component.h>
 
 namespace ROS2

+ 2 - 2
Gems/ROS2/Code/Source/RobotControl/ROS2RobotControlComponent.cpp

@@ -7,8 +7,8 @@
  */
 
 #include "RobotControl/ROS2RobotControlComponent.h"
-#include "RobotControl/Ackermann/AckermannSubscriptionHandler.h"
-#include "RobotControl/Twist/TwistSubscriptionHandler.h"
+#include "Ackermann/AckermannSubscriptionHandler.h"
+#include "Twist/TwistSubscriptionHandler.h"
 #include <AzCore/Component/Entity.h>
 #include <AzCore/Debug/Trace.h>
 #include <AzCore/Serialization/EditContext.h>

+ 2 - 2
Gems/ROS2/Code/Source/RobotControl/ROS2RobotControlComponent.h

@@ -7,8 +7,8 @@
  */
 #pragma once
 
-#include "ControlConfiguration.h"
-#include "ControlSubscriptionHandler.h"
+#include "ROS2/RobotControl/ControlConfiguration.h"
+#include "ROS2/RobotControl/ControlSubscriptionHandler.h"
 #include <AzCore/Component/Component.h>
 #include <AzCore/std/smart_ptr/unique_ptr.h>
 #include <ROS2/Communication/TopicConfiguration.h>

+ 1 - 1
Gems/ROS2/Code/Source/RobotControl/Twist/TwistSubscriptionHandler.cpp

@@ -7,8 +7,8 @@
  */
 
 #include "TwistSubscriptionHandler.h"
+#include "ROS2/RobotControl/Twist/TwistBus.h"
 #include "ROS2/Utilities/ROS2Conversions.h"
-#include "TwistBus.h"
 
 namespace ROS2
 {

+ 1 - 1
Gems/ROS2/Code/Source/RobotControl/Twist/TwistSubscriptionHandler.h

@@ -7,7 +7,7 @@
  */
 #pragma once
 
-#include "RobotControl/ControlSubscriptionHandler.h"
+#include "ROS2/RobotControl/ControlSubscriptionHandler.h"
 #include <geometry_msgs/msg/twist.hpp>
 
 namespace ROS2

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

@@ -9,6 +9,7 @@
 #include "RobotImporter/URDF/URDFPrefabMaker.h"
 #include "ROS2/Frame/ROS2FrameComponent.h"
 #include "ROS2/ROS2GemUtilities.h"
+#include "ROS2/Spawner/SpawnerBus.h"
 #include "RobotControl/ROS2RobotControlComponent.h"
 #include "RobotImporter/URDF/CollidersMaker.h"
 #include "RobotImporter/URDF/PrefabMakerUtils.h"
@@ -21,8 +22,6 @@
 #include <AzToolsFramework/ToolsComponents/GenericComponentWrapper.h>
 #include <AzToolsFramework/ToolsComponents/TransformComponent.h>
 
-#include <Spawner/SpawnerBus.h>
-
 namespace ROS2
 {
     URDFPrefabMaker::URDFPrefabMaker(const AZStd::string& modelFilePath, urdf::ModelInterfaceSharedPtr model, AZStd::string prefabPath)

+ 1 - 1
Gems/ROS2/Code/Source/Sensor/ROS2SensorComponent.cpp

@@ -6,7 +6,7 @@
  *
  */
 
-#include "Sensor/ROS2SensorComponent.h"
+#include "ROS2/Sensor/ROS2SensorComponent.h"
 #include "ROS2/Frame/ROS2FrameComponent.h"
 #include "ROS2/ROS2Bus.h"
 #include "ROS2/ROS2GemUtilities.h"

+ 1 - 1
Gems/ROS2/Code/Source/Sensor/SensorConfiguration.cpp

@@ -6,7 +6,7 @@
  *
  */
 
-#include "Sensor/SensorConfiguration.h"
+#include "ROS2/Sensor/SensorConfiguration.h"
 #include <AzCore/Serialization/EditContext.h>
 #include <AzCore/Serialization/EditContextConstants.inl>
 

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

@@ -7,8 +7,8 @@
  */
 #pragma once
 
+#include "ROS2/Spawner/SpawnerBus.h"
 #include "ROS2SpawnPointComponent.h"
-#include "SpawnerBus.h"
 #include <AzCore/Asset/AssetCommon.h>
 #include <AzCore/Asset/AssetSerializer.h>
 #include <AzCore/Component/Component.h>

+ 1 - 10
Gems/ROS2/Code/ros2_files.cmake

@@ -34,39 +34,30 @@ set(FILES
         Source/Lidar/LidarTemplateUtils.h
         Source/Lidar/ROS2LidarSensorComponent.cpp
         Source/Lidar/ROS2LidarSensorComponent.h
-        Source/Manipulator/MotorizedJoint.cpp
+        Source/Manipulator/MotorizedJointComponent.cpp
         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
         Source/Sensor/ROS2SensorComponent.cpp
-        Source/Sensor/ROS2SensorComponent.h
         Source/Sensor/SensorConfiguration.cpp
-        Source/Sensor/SensorConfiguration.h
         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/VehicleDynamics/AxleConfiguration.cpp

+ 6 - 1
Gems/ROS2/Code/ros2_header_files.cmake

@@ -7,9 +7,14 @@ set(FILES
         Include/ROS2/Frame/NamespaceConfiguration.h
         Include/ROS2/Frame/ROS2FrameComponent.h
         Include/ROS2/Frame/ROS2Transform.h
+        Include/ROS2/Manipulator/MotorizedJointComponent.h
+        Include/ROS2/RobotControl/ControlConfiguration.h
+        Include/ROS2/RobotControl/ControlSubscriptionHandler.h
         Include/ROS2/ROS2Bus.h
         Include/ROS2/ROS2GemUtilities.h
-        Include/ROS2/Manipulator/MotorizedJoint.h
+        Include/ROS2/Sensor/ROS2SensorComponent.h
+        Include/ROS2/Sensor/SensorConfiguration.h
+        Include/ROS2/Spawner/SpawnerBus.h
         Include/ROS2/Utilities/ROS2Conversions.h
         Include/ROS2/Utilities/ROS2Names.h
         Include/ROS2/VehicleDynamics/DriveModels/PidConfiguration.h