diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 1bac9e922b..ad8b8e3a75 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -11,7 +11,7 @@ if(NOT CMAKE_CXX_COMPILER_ID STREQUAL "MSVC") -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wcast-qual -Wno-unused-parameter -Wno-unused-function) else() - add_compile_options(/W3) + add_compile_options(/W3 /wd4251 /wd4068 /wd4275) endif() if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") diff --git a/moveit_core/robot_state/CMakeLists.txt b/moveit_core/robot_state/CMakeLists.txt index ba5b60d493..4d0a5966f6 100644 --- a/moveit_core/robot_state/CMakeLists.txt +++ b/moveit_core/robot_state/CMakeLists.txt @@ -47,7 +47,7 @@ if(BUILD_TESTING) include_directories(${moveit_resources_INCLUDE_DIRS}) if(WIN32) - # TODO add windows paths + add_compile_definitions(_USE_MATH_DEFINES /wd4251 /wd4068 /wd4275) else() set(append_library_dirs "${CMAKE_CURRENT_BINARY_DIR};${CMAKE_CURRENT_BINARY_DIR}/../utils") endif() diff --git a/moveit_core/utils/CMakeLists.txt b/moveit_core/utils/CMakeLists.txt index 44e63212f7..c9ab9b8865 100644 --- a/moveit_core/utils/CMakeLists.txt +++ b/moveit_core/utils/CMakeLists.txt @@ -1,6 +1,6 @@ set(MOVEIT_LIB_NAME moveit_utils) -add_library(${MOVEIT_LIB_NAME} SHARED +add_library(${MOVEIT_LIB_NAME} src/lexical_casts.cpp src/message_checks.cpp src/rclcpp_utils.cpp @@ -8,7 +8,6 @@ add_library(${MOVEIT_LIB_NAME} SHARED ament_target_dependencies(${MOVEIT_LIB_NAME} Boost moveit_msgs) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib @@ -21,7 +20,7 @@ if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) find_package(moveit_resources REQUIRED) set(MOVEIT_TEST_LIB_NAME moveit_test_utils) - add_library(${MOVEIT_TEST_LIB_NAME} SHARED + add_library(${MOVEIT_TEST_LIB_NAME} src/robot_model_test_utils.cpp) ament_target_dependencies(${MOVEIT_TEST_LIB_NAME} Boost @@ -34,8 +33,7 @@ if(BUILD_TESTING) ) set_target_properties(${MOVEIT_TEST_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") - set_target_properties(${MOVEIT_TEST_LIB_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS TRUE) - + ament_export_libraries(${MOVEIT_TEST_LIB_NAME} ${MOVEIT_LIB_NAME}) ament_export_include_directories(include) diff --git a/moveit_demo_nodes/run_moveit_cpp/CMakeLists.txt b/moveit_demo_nodes/run_moveit_cpp/CMakeLists.txt index 820b4af675..86a7e4d033 100644 --- a/moveit_demo_nodes/run_moveit_cpp/CMakeLists.txt +++ b/moveit_demo_nodes/run_moveit_cpp/CMakeLists.txt @@ -10,6 +10,11 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() +if (WIN32) + add_compile_options(/wd4251 /wd4068 /wd4275) +endif() + + # find dependencies find_package(ament_cmake REQUIRED) find_package(moveit_ros_planning_interface REQUIRED)