Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 12 additions & 0 deletions controller_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,15 @@ target_link_libraries(controller_interface PUBLIC
fmt::fmt)

if(BUILD_TESTING)
function(add_atomic_link_options target)
if(CMAKE_SYSTEM_PROCESSOR STREQUAL "loongarch64")
target_link_options(${target} PRIVATE
"LINKER:--no-as-needed"
"LINKER:-latomic"
"LINKER:--as-needed"
)
endif()
endfunction()
find_package(ament_cmake_gmock REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
Expand All @@ -44,11 +53,13 @@ if(BUILD_TESTING)
target_link_libraries(test_controller_interface
controller_interface
)
add_atomic_link_options(test_controller_interface)

ament_add_gmock(test_controller_with_options test/test_controller_with_options.cpp)
target_link_libraries(test_controller_with_options
controller_interface
)
add_atomic_link_options(test_controller_with_options)
target_compile_definitions(
test_controller_with_options
PRIVATE PARAMETERS_FILE_PATH="${CMAKE_CURRENT_LIST_DIR}/test/")
Expand All @@ -58,6 +69,7 @@ if(BUILD_TESTING)
controller_interface
hardware_interface::hardware_interface
)
add_atomic_link_options(test_chainable_controller_interface)

ament_add_gmock(test_semantic_component_interface test/test_semantic_component_interface.cpp)
target_link_libraries(test_semantic_component_interface
Expand Down
21 changes: 21 additions & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -54,10 +54,20 @@ target_link_libraries(controller_manager PUBLIC
${std_msgs_TARGETS}
${controller_manager_msgs_TARGETS})

function(add_atomic_link_options target)
if(CMAKE_SYSTEM_PROCESSOR STREQUAL "loongarch64")
target_link_options(${target} PRIVATE
"LINKER:--no-as-needed"
"LINKER:-latomic"
"LINKER:--as-needed"
)
endif()
endfunction()
add_executable(ros2_control_node src/ros2_control_node.cpp)
target_link_libraries(ros2_control_node PRIVATE
controller_manager
)
add_atomic_link_options(ros2_control_node)

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
Expand Down Expand Up @@ -109,6 +119,7 @@ if(BUILD_TESTING)
test_chainable_controller
ros2_control_test_assets::ros2_control_test_assets
)
add_atomic_link_options(test_controller_manager)

ament_add_gmock(test_controller_manager_with_namespace
test/test_controller_manager_with_namespace.cpp
Expand All @@ -118,6 +129,7 @@ if(BUILD_TESTING)
test_controller
ros2_control_test_assets::ros2_control_test_assets
)
add_atomic_link_options(test_controller_manager_with_namespace)

ament_add_gmock(test_controller_manager_hardware_error_handling
test/test_controller_manager_hardware_error_handling.cpp
Expand All @@ -127,6 +139,7 @@ if(BUILD_TESTING)
test_controller
ros2_control_test_assets::ros2_control_test_assets
)
add_atomic_link_options(test_controller_manager_hardware_error_handling)

ament_add_gmock(test_load_controller
test/test_load_controller.cpp
Expand All @@ -138,6 +151,7 @@ if(BUILD_TESTING)
test_controller_failed_init
ros2_control_test_assets::ros2_control_test_assets
)
add_atomic_link_options(test_load_controller)

ament_add_gmock(test_controllers_chaining_with_controller_manager
test/test_controllers_chaining_with_controller_manager.cpp
Expand All @@ -148,6 +162,7 @@ if(BUILD_TESTING)
test_controller
ros2_control_test_assets::ros2_control_test_assets
)
add_atomic_link_options(test_controllers_chaining_with_controller_manager)

ament_add_gmock(test_controller_manager_srvs
test/test_controller_manager_srvs.cpp
Expand All @@ -160,6 +175,7 @@ if(BUILD_TESTING)
ros2_control_test_assets::ros2_control_test_assets
${controller_manager_msgs_TARGETS}
)
add_atomic_link_options(test_controller_manager_srvs)
set_tests_properties(test_controller_manager_srvs PROPERTIES TIMEOUT 120)
ament_add_gmock(test_controller_manager_urdf_passing
test/test_controller_manager_urdf_passing.cpp
Expand All @@ -170,6 +186,7 @@ if(BUILD_TESTING)
ros2_control_test_assets::ros2_control_test_assets
${controller_manager_msgs_TARGETS}
)
add_atomic_link_options(test_controller_manager_urdf_passing)

add_library(test_controller_with_interfaces SHARED
test/test_controller_with_interfaces/test_controller_with_interfaces.cpp
Expand All @@ -194,6 +211,7 @@ if(BUILD_TESTING)
test_controller_with_interfaces
ros2_control_test_assets::ros2_control_test_assets
)
add_atomic_link_options(test_release_interfaces)

ament_add_gmock(test_spawner_unspawner
test/test_spawner_unspawner.cpp
Expand All @@ -204,6 +222,7 @@ if(BUILD_TESTING)
test_controller
ros2_control_test_assets::ros2_control_test_assets
)
add_atomic_link_options(test_spawner_unspawner)
target_compile_definitions(
test_spawner_unspawner
PRIVATE PARAMETERS_FILE_PATH="${CMAKE_CURRENT_LIST_DIR}/test/")
Expand All @@ -217,6 +236,7 @@ if(BUILD_TESTING)
test_controller
ros2_control_test_assets::ros2_control_test_assets
)
add_atomic_link_options(test_hardware_spawner)

ament_add_gmock(test_hardware_management_srvs
test/test_hardware_management_srvs.cpp
Expand All @@ -227,6 +247,7 @@ if(BUILD_TESTING)
ros2_control_test_assets::ros2_control_test_assets
${controller_manager_msgs_TARGETS}
)
add_atomic_link_options(test_hardware_management_srvs)

find_package(ament_cmake_pytest REQUIRED)
install(FILES test/test_ros2_control_node.yaml
Expand Down
15 changes: 15 additions & 0 deletions hardware_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,15 @@ pluginlib_export_plugin_description_file(
hardware_interface mock_components_plugin_description.xml)

if(BUILD_TESTING)
function(add_atomic_link_options target)
if(CMAKE_SYSTEM_PROCESSOR STREQUAL "loongarch64")
target_link_options(${target} PRIVATE
"LINKER:--no-as-needed"
"LINKER:-latomic"
"LINKER:--as-needed"
)
endif()
endfunction()

find_package(ament_cmake_gmock REQUIRED)
find_package(ros2_control_test_assets REQUIRED)
Expand All @@ -83,6 +92,7 @@ if(BUILD_TESTING)

ament_add_gmock(test_joint_handle test/test_handle.cpp)
target_link_libraries(test_joint_handle hardware_interface rcpputils::rcpputils)
add_atomic_link_options(test_joint_handle)

# Test helper methods
ament_add_gmock(test_helpers test/test_helpers.cpp)
Expand All @@ -91,15 +101,19 @@ if(BUILD_TESTING)
# Test lexical casts methods
ament_add_gtest(test_lexical_casts test/test_lexical_casts.cpp)
target_link_libraries(test_lexical_casts hardware_interface)
add_atomic_link_options(test_lexical_casts)

ament_add_gmock(test_component_interfaces test/test_component_interfaces.cpp)
target_link_libraries(test_component_interfaces hardware_interface ros2_control_test_assets::ros2_control_test_assets)
add_atomic_link_options(test_component_interfaces)

ament_add_gmock(test_component_interfaces_custom_export test/test_component_interfaces_custom_export.cpp)
target_link_libraries(test_component_interfaces_custom_export hardware_interface ros2_control_test_assets::ros2_control_test_assets)
add_atomic_link_options(test_component_interfaces_custom_export)

ament_add_gmock(test_component_parser test/test_component_parser.cpp)
target_link_libraries(test_component_parser hardware_interface ros2_control_test_assets::ros2_control_test_assets)
add_atomic_link_options(test_component_parser)

add_library(test_hardware_components SHARED
test/test_hardware_components/test_single_joint_actuator.cpp
Expand All @@ -119,6 +133,7 @@ if(BUILD_TESTING)
ament_add_gmock(test_generic_system test/mock_components/test_generic_system.cpp)
target_include_directories(test_generic_system PRIVATE include)
target_link_libraries(test_generic_system hardware_interface ros2_control_test_assets::ros2_control_test_assets)
add_atomic_link_options(test_generic_system)
endif()

install(
Expand Down
11 changes: 11 additions & 0 deletions hardware_interface_testing/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,15 @@ pluginlib_export_plugin_description_file(
hardware_interface test/test_components/test_components.xml)

if(BUILD_TESTING)
function(add_atomic_link_options target)
if(CMAKE_SYSTEM_PROCESSOR STREQUAL "loongarch64")
target_link_options(${target} PRIVATE
"LINKER:--no-as-needed"
"LINKER:-latomic"
"LINKER:--as-needed"
)
endif()
endfunction()

find_package(ament_cmake_gmock REQUIRED)

Expand All @@ -47,13 +56,15 @@ if(BUILD_TESTING)
rclcpp_lifecycle::rclcpp_lifecycle
ros2_control_test_assets::ros2_control_test_assets
${lifecycle_msgs_TARGETS})
add_atomic_link_options(test_resource_manager)

ament_add_gmock(test_resource_manager_prepare_perform_switch test/test_resource_manager_prepare_perform_switch.cpp)
target_link_libraries(test_resource_manager_prepare_perform_switch
hardware_interface::hardware_interface
rclcpp_lifecycle::rclcpp_lifecycle
ros2_control_test_assets::ros2_control_test_assets
${lifecycle_msgs_TARGETS})
add_atomic_link_options(test_resource_manager_prepare_perform_switch)

endif()

Expand Down
13 changes: 13 additions & 0 deletions transmission_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,16 @@ target_link_libraries(transmission_interface PUBLIC
pluginlib_export_plugin_description_file(transmission_interface ros2_control_plugins.xml)

if(BUILD_TESTING)
function(add_atomic_link_options target)
if(CMAKE_SYSTEM_PROCESSOR STREQUAL "loongarch64")
target_link_options(${target} PRIVATE
"LINKER:--no-as-needed"
"LINKER:-latomic"
"LINKER:--as-needed"
)
endif()
endfunction()

find_package(ament_cmake_gmock REQUIRED)
find_package(ros2_control_test_assets REQUIRED)

Expand All @@ -59,20 +69,23 @@ if(BUILD_TESTING)
target_link_libraries(test_simple_transmission_loader
transmission_interface
ros2_control_test_assets::ros2_control_test_assets)
add_atomic_link_options(test_simple_transmission_loader)

ament_add_gmock(test_four_bar_linkage_transmission_loader
test/four_bar_linkage_transmission_loader_test.cpp
)
target_link_libraries(test_four_bar_linkage_transmission_loader
transmission_interface
ros2_control_test_assets::ros2_control_test_assets)
add_atomic_link_options(test_four_bar_linkage_transmission_loader)

ament_add_gmock(test_differential_transmission_loader
test/differential_transmission_loader_test.cpp
)
target_link_libraries(test_differential_transmission_loader
transmission_interface
ros2_control_test_assets::ros2_control_test_assets)
add_atomic_link_options(test_differential_transmission_loader)

ament_add_gmock(
test_utils
Expand Down