@@ -54,10 +54,20 @@ target_link_libraries(controller_manager PUBLIC
5454 ${std_msgs_TARGETS}
5555 ${controller_manager_msgs_TARGETS} )
5656
57+ function (add_atomic_link_options target )
58+ if (CMAKE_SYSTEM_PROCESSOR STREQUAL "loongarch64" )
59+ target_link_options (${target} PRIVATE
60+ "LINKER:--no-as-needed"
61+ "LINKER:-latomic"
62+ "LINKER:--as-needed"
63+ )
64+ endif ()
65+ endfunction ()
5766add_executable (ros2_control_node src/ros2_control_node.cpp)
5867target_link_libraries (ros2_control_node PRIVATE
5968 controller_manager
6069)
70+ add_atomic_link_options(ros2_control_node)
6171
6272if (BUILD_TESTING)
6373 find_package (ament_cmake_gmock REQUIRED)
@@ -109,6 +119,7 @@ if(BUILD_TESTING)
109119 test_chainable_controller
110120 ros2_control_test_assets::ros2_control_test_assets
111121 )
122+ add_atomic_link_options(test_controller_manager)
112123
113124 ament_add_gmock(test_controller_manager_with_namespace
114125 test /test_controller_manager_with_namespace.cpp
@@ -118,6 +129,7 @@ if(BUILD_TESTING)
118129 test_controller
119130 ros2_control_test_assets::ros2_control_test_assets
120131 )
132+ add_atomic_link_options(test_controller_manager_with_namespace)
121133
122134 ament_add_gmock(test_controller_manager_hardware_error_handling
123135 test /test_controller_manager_hardware_error_handling.cpp
@@ -127,6 +139,7 @@ if(BUILD_TESTING)
127139 test_controller
128140 ros2_control_test_assets::ros2_control_test_assets
129141 )
142+ add_atomic_link_options(test_controller_manager_hardware_error_handling)
130143
131144 ament_add_gmock(test_load_controller
132145 test /test_load_controller.cpp
@@ -138,6 +151,7 @@ if(BUILD_TESTING)
138151 test_controller_failed_init
139152 ros2_control_test_assets::ros2_control_test_assets
140153 )
154+ add_atomic_link_options(test_load_controller)
141155
142156 ament_add_gmock(test_controllers_chaining_with_controller_manager
143157 test /test_controllers_chaining_with_controller_manager.cpp
@@ -148,6 +162,7 @@ if(BUILD_TESTING)
148162 test_controller
149163 ros2_control_test_assets::ros2_control_test_assets
150164 )
165+ add_atomic_link_options(test_controllers_chaining_with_controller_manager)
151166
152167 ament_add_gmock(test_controller_manager_srvs
153168 test /test_controller_manager_srvs.cpp
@@ -160,6 +175,7 @@ if(BUILD_TESTING)
160175 ros2_control_test_assets::ros2_control_test_assets
161176 ${controller_manager_msgs_TARGETS}
162177 )
178+ add_atomic_link_options(test_controller_manager_srvs)
163179 set_tests_properties (test_controller_manager_srvs PROPERTIES TIMEOUT 120)
164180 ament_add_gmock(test_controller_manager_urdf_passing
165181 test /test_controller_manager_urdf_passing.cpp
@@ -170,6 +186,7 @@ if(BUILD_TESTING)
170186 ros2_control_test_assets::ros2_control_test_assets
171187 ${controller_manager_msgs_TARGETS}
172188 )
189+ add_atomic_link_options(test_controller_manager_urdf_passing)
173190
174191 add_library (test_controller_with_interfaces SHARED
175192 test /test_controller_with_interfaces/test_controller_with_interfaces.cpp
@@ -194,6 +211,7 @@ if(BUILD_TESTING)
194211 test_controller_with_interfaces
195212 ros2_control_test_assets::ros2_control_test_assets
196213 )
214+ add_atomic_link_options(test_release_interfaces)
197215
198216 ament_add_gmock(test_spawner_unspawner
199217 test /test_spawner_unspawner.cpp
@@ -204,6 +222,7 @@ if(BUILD_TESTING)
204222 test_controller
205223 ros2_control_test_assets::ros2_control_test_assets
206224 )
225+ add_atomic_link_options(test_spawner_unspawner)
207226 target_compile_definitions (
208227 test_spawner_unspawner
209228 PRIVATE PARAMETERS_FILE_PATH="${CMAKE_CURRENT_LIST_DIR} /test/" )
@@ -217,6 +236,7 @@ if(BUILD_TESTING)
217236 test_controller
218237 ros2_control_test_assets::ros2_control_test_assets
219238 )
239+ add_atomic_link_options(test_hardware_spawner)
220240
221241 ament_add_gmock(test_hardware_management_srvs
222242 test /test_hardware_management_srvs.cpp
@@ -227,6 +247,7 @@ if(BUILD_TESTING)
227247 ros2_control_test_assets::ros2_control_test_assets
228248 ${controller_manager_msgs_TARGETS}
229249 )
250+ add_atomic_link_options(test_hardware_management_srvs)
230251
231252 find_package (ament_cmake_pytest REQUIRED)
232253 install (FILES test /test_ros2_control_node.yaml
0 commit comments