Skip to content

Commit 9693964

Browse files
zhaixiaojuanqiangxuhui
authored andcommitted
Fix atomic error on loongarch64
1 parent 783558f commit 9693964

File tree

5 files changed

+72
-0
lines changed

5 files changed

+72
-0
lines changed

controller_interface/CMakeLists.txt

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,15 @@ target_link_libraries(controller_interface PUBLIC
3535
fmt::fmt)
3636

3737
if(BUILD_TESTING)
38+
function(add_atomic_link_options target)
39+
if(CMAKE_SYSTEM_PROCESSOR STREQUAL "loongarch64")
40+
target_link_options(${target} PRIVATE
41+
"LINKER:--no-as-needed"
42+
"LINKER:-latomic"
43+
"LINKER:--as-needed"
44+
)
45+
endif()
46+
endfunction()
3847
find_package(ament_cmake_gmock REQUIRED)
3948
find_package(geometry_msgs REQUIRED)
4049
find_package(sensor_msgs REQUIRED)
@@ -44,11 +53,13 @@ if(BUILD_TESTING)
4453
target_link_libraries(test_controller_interface
4554
controller_interface
4655
)
56+
add_atomic_link_options(test_controller_interface)
4757

4858
ament_add_gmock(test_controller_with_options test/test_controller_with_options.cpp)
4959
target_link_libraries(test_controller_with_options
5060
controller_interface
5161
)
62+
add_atomic_link_options(test_controller_with_options)
5263
target_compile_definitions(
5364
test_controller_with_options
5465
PRIVATE PARAMETERS_FILE_PATH="${CMAKE_CURRENT_LIST_DIR}/test/")
@@ -58,6 +69,7 @@ if(BUILD_TESTING)
5869
controller_interface
5970
hardware_interface::hardware_interface
6071
)
72+
add_atomic_link_options(test_chainable_controller_interface)
6173

6274
ament_add_gmock(test_semantic_component_interface test/test_semantic_component_interface.cpp)
6375
target_link_libraries(test_semantic_component_interface

controller_manager/CMakeLists.txt

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -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()
5766
add_executable(ros2_control_node src/ros2_control_node.cpp)
5867
target_link_libraries(ros2_control_node PRIVATE
5968
controller_manager
6069
)
70+
add_atomic_link_options(ros2_control_node)
6171

6272
if(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

hardware_interface/CMakeLists.txt

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -70,6 +70,15 @@ pluginlib_export_plugin_description_file(
7070
hardware_interface mock_components_plugin_description.xml)
7171

7272
if(BUILD_TESTING)
73+
function(add_atomic_link_options target)
74+
if(CMAKE_SYSTEM_PROCESSOR STREQUAL "loongarch64")
75+
target_link_options(${target} PRIVATE
76+
"LINKER:--no-as-needed"
77+
"LINKER:-latomic"
78+
"LINKER:--as-needed"
79+
)
80+
endif()
81+
endfunction()
7382

7483
find_package(ament_cmake_gmock REQUIRED)
7584
find_package(ros2_control_test_assets REQUIRED)
@@ -83,6 +92,7 @@ if(BUILD_TESTING)
8392

8493
ament_add_gmock(test_joint_handle test/test_handle.cpp)
8594
target_link_libraries(test_joint_handle hardware_interface rcpputils::rcpputils)
95+
add_atomic_link_options(test_joint_handle)
8696

8797
# Test helper methods
8898
ament_add_gmock(test_helpers test/test_helpers.cpp)
@@ -91,15 +101,19 @@ if(BUILD_TESTING)
91101
# Test lexical casts methods
92102
ament_add_gtest(test_lexical_casts test/test_lexical_casts.cpp)
93103
target_link_libraries(test_lexical_casts hardware_interface)
104+
add_atomic_link_options(test_lexical_casts)
94105

95106
ament_add_gmock(test_component_interfaces test/test_component_interfaces.cpp)
96107
target_link_libraries(test_component_interfaces hardware_interface ros2_control_test_assets::ros2_control_test_assets)
108+
add_atomic_link_options(test_component_interfaces)
97109

98110
ament_add_gmock(test_component_interfaces_custom_export test/test_component_interfaces_custom_export.cpp)
99111
target_link_libraries(test_component_interfaces_custom_export hardware_interface ros2_control_test_assets::ros2_control_test_assets)
112+
add_atomic_link_options(test_component_interfaces_custom_export)
100113

101114
ament_add_gmock(test_component_parser test/test_component_parser.cpp)
102115
target_link_libraries(test_component_parser hardware_interface ros2_control_test_assets::ros2_control_test_assets)
116+
add_atomic_link_options(test_component_parser)
103117

104118
add_library(test_hardware_components SHARED
105119
test/test_hardware_components/test_single_joint_actuator.cpp
@@ -119,6 +133,7 @@ if(BUILD_TESTING)
119133
ament_add_gmock(test_generic_system test/mock_components/test_generic_system.cpp)
120134
target_include_directories(test_generic_system PRIVATE include)
121135
target_link_libraries(test_generic_system hardware_interface ros2_control_test_assets::ros2_control_test_assets)
136+
add_atomic_link_options(test_generic_system)
122137
endif()
123138

124139
install(

hardware_interface_testing/CMakeLists.txt

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,15 @@ pluginlib_export_plugin_description_file(
3838
hardware_interface test/test_components/test_components.xml)
3939

4040
if(BUILD_TESTING)
41+
function(add_atomic_link_options target)
42+
if(CMAKE_SYSTEM_PROCESSOR STREQUAL "loongarch64")
43+
target_link_options(${target} PRIVATE
44+
"LINKER:--no-as-needed"
45+
"LINKER:-latomic"
46+
"LINKER:--as-needed"
47+
)
48+
endif()
49+
endfunction()
4150

4251
find_package(ament_cmake_gmock REQUIRED)
4352

@@ -47,13 +56,15 @@ if(BUILD_TESTING)
4756
rclcpp_lifecycle::rclcpp_lifecycle
4857
ros2_control_test_assets::ros2_control_test_assets
4958
${lifecycle_msgs_TARGETS})
59+
add_atomic_link_options(test_resource_manager)
5060

5161
ament_add_gmock(test_resource_manager_prepare_perform_switch test/test_resource_manager_prepare_perform_switch.cpp)
5262
target_link_libraries(test_resource_manager_prepare_perform_switch
5363
hardware_interface::hardware_interface
5464
rclcpp_lifecycle::rclcpp_lifecycle
5565
ros2_control_test_assets::ros2_control_test_assets
5666
${lifecycle_msgs_TARGETS})
67+
add_atomic_link_options(test_resource_manager_prepare_perform_switch)
5768

5869
endif()
5970

transmission_interface/CMakeLists.txt

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,16 @@ target_link_libraries(transmission_interface PUBLIC
3535
pluginlib_export_plugin_description_file(transmission_interface ros2_control_plugins.xml)
3636

3737
if(BUILD_TESTING)
38+
function(add_atomic_link_options target)
39+
if(CMAKE_SYSTEM_PROCESSOR STREQUAL "loongarch64")
40+
target_link_options(${target} PRIVATE
41+
"LINKER:--no-as-needed"
42+
"LINKER:-latomic"
43+
"LINKER:--as-needed"
44+
)
45+
endif()
46+
endfunction()
47+
3848
find_package(ament_cmake_gmock REQUIRED)
3949
find_package(ros2_control_test_assets REQUIRED)
4050

@@ -59,20 +69,23 @@ if(BUILD_TESTING)
5969
target_link_libraries(test_simple_transmission_loader
6070
transmission_interface
6171
ros2_control_test_assets::ros2_control_test_assets)
72+
add_atomic_link_options(test_simple_transmission_loader)
6273

6374
ament_add_gmock(test_four_bar_linkage_transmission_loader
6475
test/four_bar_linkage_transmission_loader_test.cpp
6576
)
6677
target_link_libraries(test_four_bar_linkage_transmission_loader
6778
transmission_interface
6879
ros2_control_test_assets::ros2_control_test_assets)
80+
add_atomic_link_options(test_four_bar_linkage_transmission_loader)
6981

7082
ament_add_gmock(test_differential_transmission_loader
7183
test/differential_transmission_loader_test.cpp
7284
)
7385
target_link_libraries(test_differential_transmission_loader
7486
transmission_interface
7587
ros2_control_test_assets::ros2_control_test_assets)
88+
add_atomic_link_options(test_differential_transmission_loader)
7689

7790
ament_add_gmock(
7891
test_utils

0 commit comments

Comments
 (0)