Browse Source

Added CMAKE logic to disable Contact Sensor and Spawner components. (#842)

Components will be disabled when gazebo_msgs is no longer available.
Apply suggestions from code review
---------
Signed-off-by: Michał Pełka <[email protected]>
Co-authored-by: Jan Hanca <[email protected]>
Michał Pełka 4 months ago
parent
commit
01f01987c9

+ 19 - 1
Gems/ROS2/Code/CMakeLists.txt

@@ -42,6 +42,18 @@ add_custom_target(
     COMMAND ${CMAKE_COMMAND} -DROS_DISTRO=${ROS_DISTRO} -P ${CMAKE_CURRENT_SOURCE_DIR}/checkROS2Distribution.cmake
 )
 
+# Gazebo messages are optional, so we will only add the dependents if the package is found.
+# The gazebo_msgs package is EOL and will not be available in ROS 2 Kilted Kaiju.
+# If you need to use ContactSensor and/or ROS2 Spawner, please consider building gazebo_msgs from the source.
+find_package(gazebo_msgs QUIET)
+if (gazebo_msgs_FOUND)
+    message(STATUS "Found gazebo_msgs package, enabling legacy features like ContactSensor Component and ROS2 Spawner Component")
+    SET (WITH_GAZEBO_MSGS TRUE)
+else()
+    message(STATUS "Could not find gazebo_msgs package, disabling legacy features like ContactSensor Component and ROS2 Spawner Component")
+    SET(WITH_GAZEBO_MSGS FALSE)
+endif()
+
 # Add the ROS2.Static target
 # Note: We include the common files and the platform specific files which are set in ros2_common_files.cmake
 # and in ${pal_dir}/ros2_${PAL_PLATFORM_NAME_LOWERCASE}_files.cmake
@@ -71,7 +83,12 @@ ly_add_target(
             Gem::LevelGeoreferencing.API
 )
 
-target_depends_on_ros2_packages(${gem_name}.Static rclcpp builtin_interfaces std_msgs sensor_msgs nav_msgs tf2_ros ackermann_msgs gazebo_msgs vision_msgs control_msgs)
+target_depends_on_ros2_packages(${gem_name}.Static rclcpp builtin_interfaces std_msgs sensor_msgs nav_msgs tf2_ros ackermann_msgs vision_msgs control_msgs)
+
+if (WITH_GAZEBO_MSGS)
+    target_depends_on_ros2_package(${gem_name}.Static gazebo_msgs REQUIRED)
+    target_compile_definitions(${gem_name}.Static PUBLIC "WITH_GAZEBO_MSGS")
+endif()
 
 ly_add_target(
     NAME ${gem_name}.API HEADERONLY
@@ -161,6 +178,7 @@ if(PAL_TRAIT_BUILD_HOST_TOOLS)
                 Gem::Atom_Feature_Common.Public
     )
 
+
     # By default, we will specify that the above target ROS2 would be used by
     # Tool and Builder type targets when this gem is enabled. If you don't want it
     # active in Tools or Builders by default, delete one or both of the following lines:

+ 3 - 1
Gems/ROS2/Code/Source/ContactSensor/ROS2ContactSensorComponent.cpp

@@ -5,7 +5,9 @@
  * SPDX-License-Identifier: Apache-2.0 OR MIT
  *
  */
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "ROS2ContactSensorComponent.h"
 #include <AzFramework/Physics/Collision/CollisionEvents.h>
 #include <AzFramework/Physics/Common/PhysicsSimulatedBody.h>

+ 3 - 0
Gems/ROS2/Code/Source/ContactSensor/ROS2ContactSensorComponent.h

@@ -7,6 +7,9 @@
  */
 
 #pragma once
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 
 #include <AzCore/Component/EntityId.h>
 #include <AzCore/RTTI/ReflectContext.h>

+ 5 - 2
Gems/ROS2/Code/Source/ROS2EditorModule.cpp

@@ -17,10 +17,11 @@
 #include <ROS2ModuleInterface.h>
 #include <RobotImporter/ROS2RobotImporterEditorSystemComponent.h>
 #include <SdfAssetBuilder/SdfAssetBuilderSystemComponent.h>
+#include <SystemComponents/ROS2EditorSystemComponent.h>
+#ifdef WITH_GAZEBO_MSGS
 #include <Spawner/ROS2SpawnPointEditorComponent.h>
 #include <Spawner/ROS2SpawnerEditorComponent.h>
-#include <SystemComponents/ROS2EditorSystemComponent.h>
-
+#endif
 void InitROS2Resources()
 {
     // Registration of Qt (ROS2.qrc) resources
@@ -46,8 +47,10 @@ namespace ROS2
                   LidarRegistrarEditorSystemComponent::CreateDescriptor(),
                   ROS2RobotImporterEditorSystemComponent::CreateDescriptor(),
                   ROS2CameraSensorEditorComponent::CreateDescriptor(),
+#ifdef WITH_GAZEBO_MSGS
                   ROS2SpawnerEditorComponent::CreateDescriptor(),
                   ROS2SpawnPointEditorComponent::CreateDescriptor(),
+#endif
                   SdfAssetBuilderSystemComponent::CreateDescriptor(),
                   JointsManipulationEditorComponent::CreateDescriptor(),
                   JointsPositionsEditorComponent::CreateDescriptor(),

+ 10 - 7
Gems/ROS2/Code/Source/ROS2ModuleInterface.h

@@ -12,7 +12,6 @@
 #include <Camera/PostProcessing/ROS2ImageEncodingConversionComponent.h>
 #include <Camera/ROS2CameraSensorComponent.h>
 #include <Camera/ROS2CameraSystemComponent.h>
-#include <ContactSensor/ROS2ContactSensorComponent.h>
 #include <GNSS/ROS2GNSSSensorComponent.h>
 #include <Gripper/FingerGripperComponent.h>
 #include <Gripper/GripperActionServerComponent.h>
@@ -39,14 +38,16 @@
 #include <RobotControl/ROS2RobotControlComponent.h>
 #include <RobotImporter/ROS2RobotImporterSystemComponent.h>
 #include <SimulationUtils/FollowingCameraComponent.h>
-#include <Spawner/ROS2SpawnPointComponent.h>
-#include <Spawner/ROS2SpawnerComponent.h>
 #include <SystemComponents/ROS2SystemComponent.h>
 #include <VehicleDynamics/ModelComponents/AckermannModelComponent.h>
 #include <VehicleDynamics/ModelComponents/SkidSteeringModelComponent.h>
 #include <VehicleDynamics/VehicleModelComponent.h>
 #include <VehicleDynamics/WheelControllerComponent.h>
-
+#ifdef WITH_GAZEBO_MSGS
+#include <Spawner/ROS2SpawnPointComponent.h>
+#include <Spawner/ROS2SpawnerComponent.h>
+#include <ContactSensor/ROS2ContactSensorComponent.h>
+#endif
 namespace ROS2
 {
     class ROS2ModuleInterface : public AZ::Module
@@ -80,8 +81,6 @@ namespace ROS2
                     RigidBodyTwistControlComponent::CreateDescriptor(),
                     SkidSteeringControlComponent::CreateDescriptor(),
                     ROS2CameraSensorComponent::CreateDescriptor(),
-                    ROS2SpawnerComponent::CreateDescriptor(),
-                    ROS2SpawnPointComponent::CreateDescriptor(),
                     VehicleDynamics::AckermannVehicleModelComponent::CreateDescriptor(),
                     VehicleDynamics::WheelControllerComponent::CreateDescriptor(),
                     VehicleDynamics::SkidSteeringModelComponent::CreateDescriptor(),
@@ -96,9 +95,13 @@ namespace ROS2
                     GripperActionServerComponent::CreateDescriptor(),
                     VacuumGripperComponent::CreateDescriptor(),
                     FingerGripperComponent::CreateDescriptor(),
-                    ROS2ContactSensorComponent::CreateDescriptor(),
                     FollowingCameraComponent::CreateDescriptor(),
                     ClassSegmentationConfigurationComponent::CreateDescriptor(),
+#ifdef WITH_GAZEBO_MSGS
+                    ROS2SpawnerComponent::CreateDescriptor(),
+                    ROS2SpawnPointComponent::CreateDescriptor(),
+                    ROS2ContactSensorComponent::CreateDescriptor(),
+#endif
                 });
         }
 

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

@@ -5,7 +5,9 @@
  * SPDX-License-Identifier: Apache-2.0 OR MIT
  *
  */
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "ROS2SpawnPointComponent.h"
 #include "Spawner/ROS2SpawnPointComponentController.h"
 #include <AzCore/Component/Entity.h>

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

@@ -6,7 +6,9 @@
  *
  */
 #pragma once
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "Spawner/ROS2SpawnPointComponentController.h"
 #include <AzCore/Component/Component.h>
 #include <AzCore/Math/Transform.h>

+ 3 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnPointComponentController.cpp

@@ -5,7 +5,9 @@
  * SPDX-License-Identifier: Apache-2.0 OR MIT
  *
  */
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "Spawner/ROS2SpawnPointComponentController.h"
 #include "Spawner/ROS2SpawnerComponentController.h"
 #include <AzCore/Component/TransformBus.h>

+ 3 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnPointComponentController.h

@@ -6,7 +6,9 @@
  *
  */
 #pragma once
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include <AzCore/Component/Component.h>
 #include <AzCore/Component/ComponentBus.h>
 #include <AzCore/Math/Transform.h>

+ 3 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnPointEditorComponent.cpp

@@ -5,7 +5,9 @@
  * SPDX-License-Identifier: Apache-2.0 OR MIT
  *
  */
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "ROS2SpawnPointEditorComponent.h"
 #include "Spawner/ROS2SpawnPointComponentController.h"
 #include "Spawner/ROS2SpawnerEditorComponent.h"

+ 3 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnPointEditorComponent.h

@@ -6,7 +6,9 @@
  *
  */
 #pragma once
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "Spawner/ROS2SpawnPointComponent.h"
 #include "Spawner/ROS2SpawnPointComponentController.h"
 #include "Spawner/ROS2SpawnerEditorComponent.h"

+ 3 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnerComponent.cpp

@@ -5,7 +5,9 @@
  * SPDX-License-Identifier: Apache-2.0 OR MIT
  *
  */
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "ROS2SpawnerComponent.h"
 #include "Spawner/ROS2SpawnerComponentController.h"
 #include <AzCore/Component/EntityId.h>

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

@@ -6,7 +6,9 @@
  *
  */
 #pragma once
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "ROS2SpawnPointComponent.h"
 #include "Spawner/ROS2SpawnerComponentController.h"
 #include <AzCore/Asset/AssetCommon.h>

+ 3 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnerComponentController.cpp

@@ -5,7 +5,9 @@
  * SPDX-License-Identifier: Apache-2.0 OR MIT
  *
  */
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "ROS2SpawnerComponentController.h"
 #include "Spawner/ROS2SpawnPointComponent.h"
 #include "Spawner/ROS2SpawnerComponent.h"

+ 3 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnerComponentController.h

@@ -7,7 +7,9 @@
  */
 
 #pragma once
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "ROS2/Spawner/SpawnerBus.h"
 #include "ROS2SpawnPointComponent.h"
 #include <AzCore/Component/ComponentBus.h>

+ 3 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnerEditorComponent.cpp

@@ -5,7 +5,9 @@
  * SPDX-License-Identifier: Apache-2.0 OR MIT
  *
  */
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "ROS2SpawnerEditorComponent.h"
 #include "AzCore/Debug/Trace.h"
 #include "ROS2SpawnPointEditorComponent.h"

+ 3 - 1
Gems/ROS2/Code/Source/Spawner/ROS2SpawnerEditorComponent.h

@@ -6,7 +6,9 @@
  *
  */
 #pragma once
-
+#ifndef WITH_GAZEBO_MSGS
+static_assert(false, "This file should not be included in the build, without WITH_GAZEBO_MSGS defined.");
+#endif
 #include "Spawner/ROS2SpawnerComponent.h"
 #include "Spawner/ROS2SpawnerComponentController.h"
 #include <AzToolsFramework/ToolsComponents/EditorComponentAdapter.h>

+ 11 - 4
Gems/ROS2/Code/ros2_editor_files.cmake

@@ -84,10 +84,6 @@ set(FILES
     Source/RobotImporter/Utils/TypeConversions.cpp
     Source/RobotImporter/Utils/TypeConversions.h
     Source/ROS2GemUtilities.cpp
-    Source/Spawner/ROS2SpawnerEditorComponent.cpp
-    Source/Spawner/ROS2SpawnerEditorComponent.h
-    Source/Spawner/ROS2SpawnPointEditorComponent.cpp
-    Source/Spawner/ROS2SpawnPointEditorComponent.h
     Source/SdfAssetBuilder/SdfAssetBuilder.cpp
     Source/SdfAssetBuilder/SdfAssetBuilder.h
     Source/SdfAssetBuilder/SdfAssetBuilderSettings.cpp
@@ -101,3 +97,14 @@ set(FILES
     Source/SystemComponents/ROS2EditorSystemComponent.cpp
     Source/SystemComponents/ROS2EditorSystemComponent.h
 )
+
+# optional, legacy features compilation
+if (WITH_GAZEBO_MSGS)
+    list(APPEND FILES
+        Source/Spawner/ROS2SpawnerEditorComponent.cpp
+        Source/Spawner/ROS2SpawnerEditorComponent.h
+        Source/Spawner/ROS2SpawnPointEditorComponent.cpp
+        Source/Spawner/ROS2SpawnPointEditorComponent.h
+    )
+endif ()
+

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

@@ -33,8 +33,6 @@ set(FILES
         Source/Communication/QoS.cpp
         Source/Communication/PublisherConfiguration.cpp
         Source/Communication/TopicConfiguration.cpp
-        Source/ContactSensor/ROS2ContactSensorComponent.cpp
-        Source/ContactSensor/ROS2ContactSensorComponent.h
         Source/Frame/NamespaceConfiguration.cpp
         Source/Frame/ROS2FrameComponent.cpp
         Source/Frame/ROS2FrameConfiguration.cpp
@@ -130,14 +128,6 @@ set(FILES
         Source/SimulationUtils/FollowingCameraConfiguration.h
         Source/SimulationUtils/FollowingCameraComponent.cpp
         Source/SimulationUtils/FollowingCameraComponent.h
-        Source/Spawner/ROS2SpawnerComponent.cpp
-        Source/Spawner/ROS2SpawnerComponent.h
-        Source/Spawner/ROS2SpawnPointComponent.cpp
-        Source/Spawner/ROS2SpawnPointComponent.h
-        Source/Spawner/ROS2SpawnerComponentController.cpp
-        Source/Spawner/ROS2SpawnerComponentController.h
-        Source/Spawner/ROS2SpawnPointComponentController.cpp
-        Source/Spawner/ROS2SpawnPointComponentController.h
         Source/SystemComponents/ROS2SystemComponent.cpp
         Source/SystemComponents/ROS2SystemComponent.h
         Source/Utilities/ArticulationsUtilities.cpp
@@ -178,3 +168,19 @@ set(FILES
         Source/VehicleDynamics/WheelControllerComponent.h
         Source/VehicleDynamics/WheelDynamicsData.h
         )
+
+# optional, legacy features compilation
+if (WITH_GAZEBO_MSGS)
+        list(APPEND FILES
+                Source/ContactSensor/ROS2ContactSensorComponent.cpp
+                Source/ContactSensor/ROS2ContactSensorComponent.h
+                Source/Spawner/ROS2SpawnerComponent.cpp
+                Source/Spawner/ROS2SpawnerComponent.h
+                Source/Spawner/ROS2SpawnPointComponent.cpp
+                Source/Spawner/ROS2SpawnPointComponent.h
+                Source/Spawner/ROS2SpawnerComponentController.cpp
+                Source/Spawner/ROS2SpawnerComponentController.h
+                Source/Spawner/ROS2SpawnPointComponentController.cpp
+                Source/Spawner/ROS2SpawnPointComponentController.h
+        )
+endif ()

+ 9 - 5
Gems/ROS2/Code/ros2_target_depends.cmake

@@ -6,12 +6,16 @@
 function(target_depends_on_ros2_package TARGET_NAME)
     list(GET ARGN 0 _package)
     find_package(${ARGN})
-    include(${${_package}_DIR}/${_package}Config.cmake OPTIONAL)
-    if (${${_package}_FOUND_AMENT_PACKAGE})
-        message(DEBUG "Package ${_package} was found (${${_package}_DIR}) version ${${_package}_VERSION} targets : ${${_package}_TARGETS}")
-        target_link_libraries(${TARGET_NAME} PUBLIC ${${_package}_TARGETS})
+    if (${${_package}_FOUND})
+        include(${${_package}_DIR}/${_package}Config.cmake OPTIONAL)
+        if (${${_package}_FOUND_AMENT_PACKAGE})
+            message(DEBUG "Package ${_package} was found (${${_package}_DIR}) version ${${_package}_VERSION} targets : ${${_package}_TARGETS}")
+            target_link_libraries(${TARGET_NAME} PUBLIC ${${_package}_TARGETS})
+        else ()
+            message(FATAL_ERROR "Package ${_package} was found (${${_package}_DIR}), but package is not an Ament package.")
+        endif ()
     else ()
-        message(FATAL_ERROR "Package ${_package} was found (${${_package}_DIR}), but package is not an Ament package.")
+        message(DEBUG "Package ${_package} was not found.")
     endif ()
 endfunction()