Skip to content

Commit

Permalink
windows fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
traversaro committed Jan 20, 2025
1 parent 96ce1be commit 84a34b9
Show file tree
Hide file tree
Showing 60 changed files with 1,608 additions and 64 deletions.
12 changes: 6 additions & 6 deletions .github/workflows/main.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,13 +20,13 @@ jobs:
python-version: '3.11' # Version range or exact version of a Python version to use, using SemVer's version range syntax
- name: Install vinca
run: |
pip install git+https://github.com/RoboStack/vinca.git@rattler-build-humble
pip install git+https://github.com/RoboStack/vinca.git
- name: Generate recipes for linux-64
run: |
git clean -fdx
cp vinca_linux_64.yaml vinca.yaml
vinca --multiple --platform linux-64
vinca --multiple --platform linux-64 --snapshot rosdistro_snapshot.yaml
- name: Generate azure pipelines for linux-64
run: |
vinca-gha --platform linux-64 --trigger-branch buildbranch_linux -d ./recipes --additional-recipes
Expand All @@ -52,7 +52,7 @@ jobs:
run: |
git clean -fdx
cp vinca_osx.yaml vinca.yaml
vinca --multiple --platform osx-64
vinca --multiple --platform osx-64 --snapshot rosdistro_snapshot.yaml
- name: Generate azure pipelines for osx-64
run: |
vinca-gha --platform osx-64 --trigger-branch buildbranch_osx -d ./recipes --additional-recipes
Expand All @@ -78,7 +78,7 @@ jobs:
run: |
git clean -fdx
cp vinca_osx_arm64.yaml vinca.yaml
vinca --multiple --platform osx-arm64
vinca --multiple --platform osx-arm64 --snapshot rosdistro_snapshot.yaml
- name: Generate azure pipelines for osx-arm64
run: |
vinca-gha --platform osx-arm64 --trigger-branch buildbranch_osx_arm64 -d ./recipes --additional-recipes
Expand All @@ -104,7 +104,7 @@ jobs:
run: |
git clean -fdx
cp vinca_win.yaml vinca.yaml
vinca --multiple --platform win-64
vinca --multiple --platform win-64 --snapshot rosdistro_snapshot.yaml
- name: Generate azure pipelines for win-64
run: |
vinca-gha --platform win-64 --trigger-branch buildbranch_win -d ./recipes --additional-recipes
Expand All @@ -130,7 +130,7 @@ jobs:
run: |
git clean -fdx
cp vinca_linux_aarch64.yaml vinca.yaml
vinca --multiple --platform linux-aarch64
vinca --multiple --platform linux-aarch64 --snapshot rosdistro_snapshot.yaml
- name: Generate azure pipelines for linux-aarch64
run: |
vinca-gha --platform linux-aarch64 --trigger-branch buildbranch_linux_aarch64 -d ./recipes --additional-recipes
Expand Down
2 changes: 1 addition & 1 deletion env/robostackenv.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,4 @@ dependencies:
- rattler-build
- pip
- pip:
- git+https://github.com/RoboStack/vinca.git@rattler-build-humble
- git+https://github.com/RoboStack/vinca.git
6 changes: 3 additions & 3 deletions patch/dependencies.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@ pcl_ros:
add_host: ["REQUIRE_OPENGL", "libboost-devel"]
rviz_rendering:
add_host: ["glew"]
behaviortree_cpp_v3:
add_host: ["libboost-devel", "cppzmq"]
behaviortree_cpp:
add_host: ["libboost-devel", "cppzmq", "zeromq", "sqlite"]
add_run: ["libboost"]
plotjuggler:
add_host: ["libxcb", "${{ 'elfutils' if linux }}", "ros-jazzy-ros-workspace"]
Expand Down Expand Up @@ -157,7 +157,7 @@ rqt_image_overlay:
add_host: ["REQUIRE_OPENGL"]
slam_toolbox:
add_build: ["${{ 'qt-main' if (build_platform != target_platform) }}"]
add_host: ["REQUIRE_OPENGL"]
add_host: ["REQUIRE_OPENGL", "blas-devel"]
vision_msgs_rviz_plugins:
add_build: ["${{ 'qt-main' if (build_platform != target_platform) }}"]
add_host: ["REQUIRE_OPENGL"]
Expand Down
11 changes: 11 additions & 0 deletions patch/ros-jazzy-angles.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index f909972..5b6b6e8 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -19,3 +19,6 @@ find_package(ament_cmake REQUIRED)
+if(WIN32)
+ target_compile_definitions(angles INTERFACE _USE_MATH_DEFINES)
+endif()

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
24 changes: 24 additions & 0 deletions patch/ros-jazzy-behaviortree-cpp.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
diff --git a/cmake/ament_build.cmake b/cmake/ament_build.cmake
index 55c3011b2..152268032 100644
--- a/cmake/ament_build.cmake
+++ b/cmake/ament_build.cmake
@@ -10,7 +10,10 @@ if(BTCPP_SQLITE_LOGGING)
find_package(SQLite3 REQUIRED)
endif()

-find_package(ament_index_cpp REQUIRED)
+find_package(ament_index_cpp REQUIRED)
+
+set(BTCPP_EXTRA_INCLUDE_DIRS ${ZeroMQ_INCLUDE_DIRS}
+ ${SQLite3_INCLUDE_DIRS})

set( BTCPP_EXTRA_LIBRARIES
$<BUILD_INTERFACE:ament_index_cpp::ament_index_cpp>
@@ -26,6 +29,7 @@ set( BTCPP_BIN_DESTINATION bin )

mark_as_advanced(
BTCPP_EXTRA_LIBRARIES
+ BTCPP_EXTRA_INCLUDE_DIRS
BTCPP_LIB_DESTINATION
BTCPP_INCLUDE_DESTINATION
BTCPP_BIN_DESTINATION )
32 changes: 32 additions & 0 deletions patch/ros-jazzy-control-toolbox.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
From 791d063ea62837e86831b7b4dda48b22e680d8cc Mon Sep 17 00:00:00 2001
From: Christoph Froehlich <[email protected]>
Date: Mon, 25 Nov 2024 20:11:09 +0000
Subject: [PATCH] Export symbols on windows

---
CMakeLists.txt | 9 +++++++--
1 file changed, 7 insertions(+), 2 deletions(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index cc1f551..30f4bad 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -7,11 +7,16 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
endif()

if(WIN32)
- # Enable Math Constants
- # https://docs.microsoft.com/en-us/cpp/c-runtime-library/math-constants?view=vs-2019
add_compile_definitions(
+ # For math constants
+ # https://docs.microsoft.com/en-us/cpp/c-runtime-library/math-constants?view=vs-2019
_USE_MATH_DEFINES
+ # Minimize Windows namespace collision
+ NOMINMAX
+ WIN32_LEAN_AND_MEAN
)
+ # set the same behavior for windows as it is on linux
+ set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
9 changes: 9 additions & 0 deletions patch/ros-jazzy-diagnostic-aggregator.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
diff --git a/diagnostic_aggregator/CMakeLists.txt b/diagnostic_aggregator/CMakeLists.txt
index 6014edf3..bbcee116 100644
--- a/diagnostic_aggregator/CMakeLists.txt
+++ b/diagnostic_aggregator/CMakeLists.txt
@@ -6,3 +6,4 @@ endif()
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)

find_package(ament_cmake REQUIRED)
find_package(diagnostic_msgs REQUIRED)
9 changes: 9 additions & 0 deletions patch/ros-jazzy-diagnostic-updater.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
diff --git a/diagnostic_updater/CMakeLists.txt b/diagnostic_updater/CMakeLists.txt
index eafa9891..9199df0d 100644
--- a/diagnostic_updater/CMakeLists.txt
+++ b/diagnostic_updater/CMakeLists.txt
@@ -6,3 +6,4 @@ endif()
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)

find_package(ament_cmake REQUIRED)
find_package(ament_cmake_ros REQUIRED)
9 changes: 9 additions & 0 deletions patch/ros-jazzy-filters.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 32b9f9f..587d5ca 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -12,3 +12,4 @@ endif()
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)

##############################################################################
# Find dependencies
22 changes: 22 additions & 0 deletions patch/ros-jazzy-forward-command-controller.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
diff --git a/forward_command_controller/CMakeLists.txt b/forward_command_controller/CMakeLists.txt
index bf027866d6..f7610c5f85 100644
--- a/forward_command_controller/CMakeLists.txt
+++ b/forward_command_controller/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.16)
-project(forward_command_controller LANGUAGES CXX)
+project(forward_command_controller)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
@@ -7,6 +7,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
-Werror=missing-braces)
endif()

+# using this instead of visibility macros
+# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)
+
set(THIS_PACKAGE_INCLUDE_DEPENDS
controller_interface
generate_parameter_library
16 changes: 16 additions & 0 deletions patch/ros-jazzy-gripper-controllers.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
diff --git a/gripper_controllers/CMakeLists.txt b/gripper_controllers/CMakeLists.txt
index 4ffdc76168..05174402d0 100644
--- a/gripper_controllers/CMakeLists.txt
+++ b/gripper_controllers/CMakeLists.txt
@@ -1,11 +1,6 @@
cmake_minimum_required(VERSION 3.16)
project(gripper_controllers)

-if(APPLE OR WIN32)
- message(WARNING "gripper controllers are not available on OSX or Windows")
- return()
-endif()
-
if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
File renamed without changes.
8 changes: 8 additions & 0 deletions patch/ros-jazzy-hardware-interface.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
diff --git a/hardware_interface/CMakeLists.txt b/hardware_interface/CMakeLists.txt
index b4e0f6cab0..50120726bb 100644
--- a/hardware_interface/CMakeLists.txt
+++ b/hardware_interface/CMakeLists.txt
@@ -57,3 +57,4 @@ target_include_directories(mock_components PUBLIC
+target_link_libraries(mock_components PUBLIC hardware_interface)
ament_target_dependencies(mock_components PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})

13 changes: 13 additions & 0 deletions patch/ros-jazzy-image-proc.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 4570eb7..54bfe64 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -6,6 +6,8 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)
+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
25 changes: 25 additions & 0 deletions patch/ros-jazzy-image-publisher.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index cb41c81..88460ba 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,6 +1,8 @@
cmake_minimum_required(VERSION 3.5)
project(image_publisher)

+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)
+
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)

diff --git a/src/image_publisher.cpp b/src/image_publisher.cpp
index 667e7209c..2f75459c1 100644
--- a/src/image_publisher.cpp
+++ b/src/image_publisher.cpp
@@ -34,3 +34,6 @@
+#ifndef _USE_MATH_DEFINES
+#define _USE_MATH_DEFINES
+#endif
#include <cmath>
#include <chrono>
#include <limits>
13 changes: 13 additions & 0 deletions patch/ros-jazzy-image-rotate.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 49c3b94..8445833 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -6,6 +6,8 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

+add_compile_definitions(_USE_MATH_DEFINES)
+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
13 changes: 13 additions & 0 deletions patch/ros-jazzy-image-view.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 27231ef..0b0246f 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -5,6 +5,8 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)
+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
12 changes: 12 additions & 0 deletions patch/ros-jazzy-io-context.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
diff --git a/io_context/CMakeLists.txt b/io_context/CMakeLists.txt
index 54804aa..3c04653 100644
--- a/io_context/CMakeLists.txt
+++ b/io_context/CMakeLists.txt
@@ -25,6 +25,7 @@ endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)

## dependencies
find_package(ament_cmake_auto REQUIRED)
12 changes: 12 additions & 0 deletions patch/ros-jazzy-joint-limits-skip.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
diff --git a/joint_limits/src/joint_soft_limiter.cpp b/joint_limits/src/joint_soft_limiter.cpp
index a2292cb033..622a320384 100644
--- a/joint_limits/src/joint_soft_limiter.cpp
+++ b/joint_limits/src/joint_soft_limiter.cpp
@@ -13,6 +13,7 @@
// limitations under the License.

/// \author Adrià Roig Moreno
+#define _USE_MATH_DEFINES
#include "joint_limits/joint_soft_limiter.hpp"

namespace joint_limits
18 changes: 18 additions & 0 deletions patch/ros-jazzy-joint-state-broadcaster.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
diff --git a/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp b/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp
index f1c532dce9..9eb7ab8a13 100644
--- a/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp
+++ b/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp
@@ -88,9 +88,13 @@ class JointStateBroadcaster : public controller_interface::ControllerInterface
const rclcpp_lifecycle::State & previous_state) override;

protected:
+ JOINT_STATE_BROADCASTER_PUBLIC
bool init_joint_data();
+ JOINT_STATE_BROADCASTER_PUBLIC
void init_joint_state_msg();
+ JOINT_STATE_BROADCASTER_PUBLIC
void init_dynamic_joint_state_msg();
+ JOINT_STATE_BROADCASTER_PUBLIC
bool use_all_available_interfaces() const;

protected:
11 changes: 11 additions & 0 deletions patch/ros-jazzy-laser-filters.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 3bb5bfd..b9f334b 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -23,1 +23,6 @@ ament_auto_add_library(laser_scan_filters SHARED src/laser_scan_filters.cpp)
+find_package(Boost REQUIRED COMPONENTS thread)
+target_link_libraries(laser_scan_filters Boost::thread)
+set_target_properties(laser_scan_filters PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS ON)
+set_target_properties(laser_filter_chains PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS ON)
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS 1)

27 changes: 10 additions & 17 deletions patch/ros-jazzy-moveit-core.win.patch
Original file line number Diff line number Diff line change
@@ -1,17 +1,10 @@
diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt
index 382dc41c70..99d49531ef 100644
--- a/moveit_core/collision_detection_fcl/CMakeLists.txt
+++ b/moveit_core/collision_detection_fcl/CMakeLists.txt
@@ -14,11 +14,11 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
urdf
urdfdom
urdfdom_headers
- LIBFCL
visualization_msgs
)
target_link_libraries(${MOVEIT_LIB_NAME}
moveit_collision_detection
+ ${LIBFCL_LINK_LIBRARIES}
)

add_library(collision_detector_fcl_plugin SHARED src/collision_detector_fcl_plugin_loader.cpp)
diff --git a/moveit_core/online_signal_smoothing/src/acceleration_filter.cpp b/moveit_core/online_signal_smoothing/src/acceleration_filter.cpp
index 3e6b3de049..3bafe55098 100644
--- a/moveit_core/online_signal_smoothing/src/acceleration_filter.cpp
+++ b/moveit_core/online_signal_smoothing/src/acceleration_filter.cpp
@@ -224,3 +224,3 @@ double jointLimitAccelerationScalingFactor(const Eigen::VectorXd& accelerations,
- min_scaling_factor = std::min(min_scaling_factor, joint_scaling_factor);
+ min_scaling_factor = (std::min)(min_scaling_factor, joint_scaling_factor);
}
++idx;
}
13 changes: 13 additions & 0 deletions patch/ros-jazzy-moveit-planners-stomp.win.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp b/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp
index b910cd3393..97350bec21 100644
--- a/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp
+++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp
@@ -168,7 +168,7 @@ CostFn getCostFunctionFromStateValidator(const StateValidatorFn& state_validator
const long kernel_start = mu - static_cast<long>(sigma) * 4;
const long kernel_end = mu + static_cast<long>(sigma) * 4;
const long bounded_kernel_start = std::max(0l, kernel_start);
- const long bounded_kernel_end = std::min(values.cols() - 1, kernel_end);
+ const long bounded_kernel_end = std::min(static_cast<long>(values.cols()) - 1, kernel_end);
for (auto j = bounded_kernel_start; j <= bounded_kernel_end; ++j)
{
costs(j) = std::exp(-std::pow(j - mu, 2) / (2 * std::pow(sigma, 2))) / (sigma * std::sqrt(2 * M_PI));
Loading

0 comments on commit 84a34b9

Please sign in to comment.