diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index f91661b0..7afc917a 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -25,6 +25,8 @@ jobs: os: ubuntu-latest - name: macOS os: macos-latest + - name: Windows + os: windows-latest steps: - uses: actions/checkout@v5 @@ -37,6 +39,7 @@ jobs: run: cargo test - name: Cargo tests (RP and JEM) + if: runner.os != 'Windows' run: | cargo test --features rp cargo test --features jem @@ -57,6 +60,9 @@ jobs: - name: macOS os: macos-latest skip_rpi_test: 1 + - name: Windows + os: windows-latest + skip_rpi_test: 1 env: DO_DOCKER: 0 SKIP_RPI_TEST: ${{ matrix.skip_rpi_test }} @@ -73,7 +79,7 @@ jobs: with: python-version: "3.12" cache: "pip" - cache-dependency-path: open-codegen/setup.py + cache-dependency-path: open-codegen/pyproject.toml - uses: egor-tensin/setup-clang@v1 if: runner.os == 'Linux' @@ -103,6 +109,20 @@ jobs: if: runner.os == 'macOS' run: bash ./ci/script.sh python-tests + - name: Install Python package + if: runner.os == 'Windows' + working-directory: open-codegen + run: | + python -m pip install --upgrade pip + python -m pip install . + + - name: Run Python test.py + if: runner.os == 'Windows' + working-directory: open-codegen + env: + PYTHONPATH: . + run: python -W ignore test/test.py -v + ros2_tests: name: ROS2 tests needs: python_tests @@ -165,6 +185,8 @@ jobs: os: ubuntu-latest - name: macOS os: macos-latest + - name: Windows + os: windows-latest env: DO_DOCKER: 0 steps: @@ -179,7 +201,22 @@ jobs: with: python-version: "3.12" cache: "pip" - cache-dependency-path: open-codegen/setup.py + cache-dependency-path: open-codegen/pyproject.toml - name: Run OCP Python tests + if: runner.os != 'Windows' run: bash ./ci/script.sh ocp-tests + + - name: Install Python package + if: runner.os == 'Windows' + working-directory: open-codegen + run: | + python -m pip install --upgrade pip + python -m pip install . + + - name: Run OCP Python tests + if: runner.os == 'Windows' + working-directory: open-codegen + env: + PYTHONPATH: . + run: python -W ignore test/test_ocp.py -v diff --git a/open-codegen/CHANGELOG.md b/open-codegen/CHANGELOG.md index 3c38beb8..5e9b79ce 100644 --- a/open-codegen/CHANGELOG.md +++ b/open-codegen/CHANGELOG.md @@ -23,6 +23,7 @@ Note: This is the Changelog file of `opengen` - the Python interface of OpEn - Added helpful `__repr__` methods to generated Python binding response/status/error objects, TCP solver response/error objects, and `GeneratedOptimizer` for easier inspection and debugging - Updated generated TCP server and C interface templates to work with the richer Rust solver error model and expose better failure information to clients. Updated auto-generated `CMakeLists.txt` file. Tighter unit tests. - ROS2 generated packages now publish detailed `error_code` and `error_message` fields, plus `STATUS_INVALID_REQUEST`, so invalid requests and solver failures are reported explicitly instead of being silently ignored +- Extended GitHub Actions CI to run Python, OCP, and generated-code tests on Windows, and fixed multiple Windows-specific code generation, path, encoding, TCP, and C/CMake compatibility issues. ## [0.10.1] - 2026-03-25 diff --git a/open-codegen/opengen/builder/ros_builder.py b/open-codegen/opengen/builder/ros_builder.py index 7db3aeb2..4b539d8b 100644 --- a/open-codegen/opengen/builder/ros_builder.py +++ b/open-codegen/opengen/builder/ros_builder.py @@ -6,6 +6,7 @@ import logging import os import shutil +import sys import jinja2 @@ -141,7 +142,7 @@ def _generate_ros_package_xml(self): template = self._template('package.xml') output_template = template.render(meta=self._meta, ros=self._ros_config) target_rospkg_path = os.path.join(target_ros_dir, "package.xml") - with open(target_rospkg_path, "w") as fh: + with open(target_rospkg_path, "w", encoding="utf-8") as fh: fh.write(output_template) def _generate_ros_cmakelists(self): @@ -151,7 +152,7 @@ def _generate_ros_cmakelists(self): template = self._template('CMakeLists.txt') output_template = template.render(meta=self._meta, ros=self._ros_config) target_rospkg_path = os.path.join(target_ros_dir, "CMakeLists.txt") - with open(target_rospkg_path, "w") as fh: + with open(target_rospkg_path, "w", encoding="utf-8") as fh: fh.write(output_template) def _copy_ros_files(self): @@ -166,7 +167,10 @@ def _copy_ros_files(self): os.path.join(self._target_dir(), header_file_name)) shutil.copyfile(original_include_file, target_include_filename) - lib_file_name = 'lib' + self._meta.optimizer_name + '.a' + if sys.platform == "win32": + lib_file_name = self._meta.optimizer_name + '.lib' + else: + lib_file_name = 'lib' + self._meta.optimizer_name + '.a' target_lib_file_name = os.path.abspath( os.path.join(target_ros_dir, 'extern_lib', lib_file_name)) original_lib_file = os.path.abspath( @@ -194,7 +198,7 @@ def _generate_ros_params_file(self): template = self._template('open_params.yaml') output_template = template.render(meta=self._meta, ros=self._ros_config) target_yaml_fname = os.path.join(target_ros_dir, "config", "open_params.yaml") - with open(target_yaml_fname, "w") as fh: + with open(target_yaml_fname, "w", encoding="utf-8") as fh: fh.write(output_template) def _generate_ros_node_header(self): @@ -208,7 +212,7 @@ def _generate_ros_node_header(self): solver_config=self._solver_config) target_rosnode_header_path = os.path.join( target_ros_dir, "include", "open_optimizer.hpp") - with open(target_rosnode_header_path, "w") as fh: + with open(target_rosnode_header_path, "w", encoding="utf-8") as fh: fh.write(output_template) def _generate_ros_node_cpp(self): @@ -221,7 +225,7 @@ def _generate_ros_node_cpp(self): ros=self._ros_config, timestamp_created=datetime.datetime.now()) target_rosnode_cpp_path = os.path.join(target_ros_dir, "src", "open_optimizer.cpp") - with open(target_rosnode_cpp_path, "w") as fh: + with open(target_rosnode_cpp_path, "w", encoding="utf-8") as fh: fh.write(output_template) def _generate_ros_launch_file(self): @@ -232,7 +236,7 @@ def _generate_ros_launch_file(self): output_template = template.render(meta=self._meta, ros=self._ros_config) target_rosnode_launch_path = os.path.join( target_ros_dir, "launch", self._launch_file_name) - with open(target_rosnode_launch_path, "w") as fh: + with open(target_rosnode_launch_path, "w", encoding="utf-8") as fh: fh.write(output_template) def _generate_ros_readme_file(self): @@ -242,7 +246,7 @@ def _generate_ros_readme_file(self): template = self._template('README.md') output_template = template.render(ros=self._ros_config) target_readme_path = os.path.join(target_ros_dir, "README.md") - with open(target_readme_path, "w") as fh: + with open(target_readme_path, "w", encoding="utf-8") as fh: fh.write(output_template) def _symbolic_link_info_message(self): diff --git a/open-codegen/opengen/config/build_config.py b/open-codegen/opengen/config/build_config.py index ee1f8f0e..fb51bf12 100644 --- a/open-codegen/opengen/config/build_config.py +++ b/open-codegen/opengen/config/build_config.py @@ -105,7 +105,11 @@ def open_version(self): @property def local_path(self): """Local path of OpEn (if any)""" - return self.__local_path + if self.__local_path is None: + return None + # Cargo.toml accepts forward slashes on Windows, while raw backslashes + # inside TOML strings are treated as escape sequences. + return self.__local_path.replace("\\", "/") @property def build_c_bindings(self): @@ -231,7 +235,7 @@ def with_open_version(self, open_version="*", local_path=None): :return: current instance of BuildConfiguration """ self.__open_version = open_version - self.__local_path = local_path + self.__local_path = None if local_path is None else str(local_path) return self def with_build_c_bindings(self, build_c_bindings=True): diff --git a/open-codegen/opengen/tcp/optimizer_tcp_manager.py b/open-codegen/opengen/tcp/optimizer_tcp_manager.py index 77c2297c..9a16a1f0 100644 --- a/open-codegen/opengen/tcp/optimizer_tcp_manager.py +++ b/open-codegen/opengen/tcp/optimizer_tcp_manager.py @@ -91,10 +91,16 @@ def __load_tcp_details(self): with open(yaml_file, 'r') as stream: self.__optimizer_details = yaml.safe_load(stream) + @staticmethod + def __client_ip_for_connection(ip): + # `0.0.0.0` is a valid bind address for the server, but it is not a + # routable destination for a client connection on Windows. + return '127.0.0.1' if ip == '0.0.0.0' else ip + @retry(tries=10, delay=1) def __obtain_socket_connection(self): tcp_data = self.__optimizer_details - ip = tcp_data['tcp']['ip'] + ip = self.__client_ip_for_connection(tcp_data['tcp']['ip']) port = tcp_data['tcp']['port'] s = socket.socket(socket.AF_INET, socket.SOCK_STREAM, 0) try: @@ -132,7 +138,7 @@ def ping(self): def __check_if_server_is_running(self): tcp_data = self.__optimizer_details - ip = tcp_data['tcp']['ip'] + ip = self.__client_ip_for_connection(tcp_data['tcp']['ip']) port = tcp_data['tcp']['port'] with socket.socket(socket.AF_INET, socket.SOCK_STREAM, 0) as s: result = 0 == s.connect_ex((ip, port)) diff --git a/open-codegen/opengen/templates/c/example_cmakelists.txt b/open-codegen/opengen/templates/c/example_cmakelists.txt index 63d2bca9..7412dae6 100644 --- a/open-codegen/opengen/templates/c/example_cmakelists.txt +++ b/open-codegen/opengen/templates/c/example_cmakelists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.5) +cmake_minimum_required(VERSION 3.10) # Project name project({{meta.optimizer_name}}) @@ -35,6 +35,21 @@ if(CMAKE_DL_LIBS) target_link_libraries(optimizer PRIVATE ${CMAKE_DL_LIBS}) endif() +if(WIN32) + # Rust static libraries built with the MSVC toolchain depend on a small set + # of Windows system libraries that must be linked by the final C executable. + target_link_libraries( + optimizer + PRIVATE + advapi32 + bcrypt + kernel32 + ntdll + userenv + ws2_32 + ) +endif() + add_custom_target(run COMMAND $ DEPENDS optimizer diff --git a/open-codegen/opengen/templates/ros/CMakeLists.txt b/open-codegen/opengen/templates/ros/CMakeLists.txt index e66a5aee..c9a7f1f7 100644 --- a/open-codegen/opengen/templates/ros/CMakeLists.txt +++ b/open-codegen/opengen/templates/ros/CMakeLists.txt @@ -29,13 +29,24 @@ include_directories( set(NODE_NAME {{ros.node_name}}) add_executable(${NODE_NAME} src/open_optimizer.cpp) +if(WIN32) + set(OPEN_STATIC_LIB ${PROJECT_SOURCE_DIR}/extern_lib/{{meta.optimizer_name}}.lib) +else() + set(OPEN_STATIC_LIB ${PROJECT_SOURCE_DIR}/extern_lib/lib{{meta.optimizer_name}}.a) +endif() target_link_libraries( ${NODE_NAME} - ${PROJECT_SOURCE_DIR}/extern_lib/lib{{meta.optimizer_name}}.a) + ${OPEN_STATIC_LIB}) +if(WIN32) + target_link_libraries( + ${NODE_NAME} + ${catkin_LIBRARIES}) +else() target_link_libraries( ${NODE_NAME} m dl ${catkin_LIBRARIES}) +endif() add_dependencies( ${NODE_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} diff --git a/open-codegen/opengen/templates/ros2/CMakeLists.txt b/open-codegen/opengen/templates/ros2/CMakeLists.txt index 10d54220..167e310a 100644 --- a/open-codegen/opengen/templates/ros2/CMakeLists.txt +++ b/open-codegen/opengen/templates/ros2/CMakeLists.txt @@ -42,12 +42,22 @@ include_directories( set(NODE_NAME {{ros.node_name}}) add_executable(${NODE_NAME} src/open_optimizer.cpp) ament_target_dependencies(${NODE_NAME} rclcpp) +if(WIN32) + set(OPEN_STATIC_LIB ${PROJECT_SOURCE_DIR}/extern_lib/{{meta.optimizer_name}}.lib) +else() + set(OPEN_STATIC_LIB ${PROJECT_SOURCE_DIR}/extern_lib/lib{{meta.optimizer_name}}.a) +endif() target_link_libraries( ${NODE_NAME} - ${PROJECT_SOURCE_DIR}/extern_lib/lib{{meta.optimizer_name}}.a - m - dl + ${OPEN_STATIC_LIB} ) +if(NOT WIN32) + target_link_libraries( + ${NODE_NAME} + m + dl + ) +endif() rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") target_link_libraries(${NODE_NAME} "${cpp_typesupport_target}") diff --git a/open-codegen/test/test.py b/open-codegen/test/test.py index 79d4373a..a88dbb1f 100644 --- a/open-codegen/test/test.py +++ b/open-codegen/test/test.py @@ -10,11 +10,26 @@ import subprocess import logging import numpy as np +from pathlib import PureWindowsPath +class BuildConfigurationTestCase(unittest.TestCase): + + def test_local_path_is_toml_safe_on_windows(self): + # some windows-type path... + windows_style_path = PureWindowsPath("C:/temp/optimization-engine") + build_config = og.config.BuildConfiguration() \ + .with_open_version(local_path=windows_style_path) + + self.assertEqual( + "C:/temp/optimization-engine", + build_config.local_path + ) + + class RustBuildTestCase(unittest.TestCase): TEST_DIR = ".python_test_build" @@ -806,6 +821,54 @@ def rebuild_generated_staticlib(optimizer_name): @staticmethod def c_bindings_helper(optimizer_name): + if sys.platform == "win32": + result = RustBuildTestCase.c_bindings_cmake_helper( + optimizer_name=optimizer_name, + build_dir_name="cmake-build-run") + compile_stdout = result["configure_stdout"] + result["build_stdout"] + compile_stderr = result["configure_stderr"] + result["build_stderr"] + compile_returncode = ( + result["configure_returncode"] + if result["configure_returncode"] != 0 + else result["build_returncode"] + ) + + run_stdout = "" + run_stderr = "" + run_returncode = None + if compile_returncode == 0: + executable_candidates = [ + os.path.join(result["build_dir"], "Debug", "optimizer.exe"), + os.path.join(result["build_dir"], "optimizer.exe"), + os.path.join(result["build_dir"], "Debug", "optimizer"), + os.path.join(result["build_dir"], "optimizer"), + ] + executable_path = next( + (candidate for candidate in executable_candidates if os.path.exists(candidate)), + None, + ) + if executable_path is None: + raise RuntimeError("Could not locate built optimizer executable") + + run_process = subprocess.Popen( + [executable_path], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + ) + run_stdout_bytes, run_stderr_bytes = run_process.communicate() + run_stdout = run_stdout_bytes.decode() + run_stderr = run_stderr_bytes.decode() + run_returncode = run_process.returncode + + return { + "compile_returncode": compile_returncode, + "compile_stdout": compile_stdout, + "compile_stderr": compile_stderr, + "run_returncode": run_returncode, + "run_stdout": run_stdout, + "run_stderr": run_stderr, + } + compile_process = subprocess.Popen( ["/usr/bin/gcc", RustBuildTestCase.TEST_DIR + "/" + optimizer_name + "/example_optimizer.c", @@ -865,13 +928,13 @@ def patch_c_bindings_example_parameter_initializer(optimizer_name, replacement_l return original_line @staticmethod - def c_bindings_cmake_helper(optimizer_name): + def c_bindings_cmake_helper(optimizer_name, build_dir_name="cmake-build-test"): cmake_executable = shutil.which("cmake") if cmake_executable is None: raise unittest.SkipTest("cmake is not available in PATH") optimizer_dir = os.path.join(RustBuildTestCase.TEST_DIR, optimizer_name) - build_dir = os.path.join(optimizer_dir, "cmake-build-test") + build_dir = os.path.join(optimizer_dir, build_dir_name) if os.path.isdir(build_dir): shutil.rmtree(build_dir) os.makedirs(build_dir) @@ -888,8 +951,11 @@ def c_bindings_cmake_helper(optimizer_name): build_stderr = b"" build_returncode = None if configure_process.returncode == 0: + build_command = [cmake_executable, "--build", "."] + if sys.platform == "win32": + build_command.extend(["--config", "Debug"]) build_process = subprocess.Popen( - [cmake_executable, "--build", "."], + build_command, cwd=build_dir, stdout=subprocess.PIPE, stderr=subprocess.PIPE, @@ -904,27 +970,37 @@ def c_bindings_cmake_helper(optimizer_name): "build_returncode": build_returncode, "build_stdout": build_stdout.decode(), "build_stderr": build_stderr.decode(), + "build_dir": build_dir, } def test_c_bindings(self): result = RustBuildTestCase.c_bindings_helper(optimizer_name="only_f1") - self.assertEqual(0, result["compile_returncode"], msg=result["compile_stderr"]) - self.assertEqual(0, result["run_returncode"], msg=result["run_stderr"]) + self.assertEqual( + 0, + result["compile_returncode"], + msg=result["compile_stdout"] + result["compile_stderr"]) + self.assertEqual(0, result["run_returncode"], msg=result["run_stdout"] + result["run_stderr"]) self.assertIn("Converged", result["run_stdout"]) self.assertIn("exit status : 0", result["run_stdout"]) self.assertIn("error code : 0", result["run_stdout"]) result = RustBuildTestCase.c_bindings_helper(optimizer_name="only_f2") - self.assertEqual(0, result["compile_returncode"], msg=result["compile_stderr"]) + self.assertEqual( + 0, + result["compile_returncode"], + msg=result["compile_stdout"] + result["compile_stderr"]) self.assertIn("Converged", result["run_stdout"]) - self.assertEqual(0, result["run_returncode"], msg=result["run_stderr"]) + self.assertEqual(0, result["run_returncode"], msg=result["run_stdout"] + result["run_stderr"]) self.assertIn("exit status : 0", result["run_stdout"]) self.assertIn("error code : 0", result["run_stdout"]) result = RustBuildTestCase.c_bindings_helper(optimizer_name="plain") self.assertIn("Converged", result["run_stdout"]) - self.assertEqual(0, result["compile_returncode"], msg=result["compile_stderr"]) - self.assertEqual(0, result["run_returncode"], msg=result["run_stderr"]) + self.assertEqual( + 0, + result["compile_returncode"], + msg=result["compile_stdout"] + result["compile_stderr"]) + self.assertEqual(0, result["run_returncode"], msg=result["run_stdout"] + result["run_stderr"]) self.assertIn("exit status : 0", result["run_stdout"]) self.assertIn("error code : 0", result["run_stdout"]) @@ -942,7 +1018,10 @@ def test_c_bindings_error_path(self): RustBuildTestCase.patch_c_bindings_example_parameter_initializer( optimizer_name="solver_error", replacement_line=original_line) - self.assertEqual(0, result["compile_returncode"], msg=result["compile_stderr"]) + self.assertEqual( + 0, + result["compile_returncode"], + msg=result["compile_stdout"] + result["compile_stderr"]) self.assertNotEqual(0, result["run_returncode"]) self.assertIn("error code : 2000", result["run_stdout"]) self.assertIn("forced solver error for TCP test", result["run_stdout"]) @@ -952,8 +1031,14 @@ def test_c_bindings_error_path(self): def test_c_bindings_cmake_example_builds(self): result = RustBuildTestCase.c_bindings_cmake_helper(optimizer_name="plain") - self.assertEqual(0, result["configure_returncode"], msg=result["configure_stderr"]) - self.assertEqual(0, result["build_returncode"], msg=result["build_stderr"]) + self.assertEqual( + 0, + result["configure_returncode"], + msg=result["configure_stdout"] + result["configure_stderr"]) + self.assertEqual( + 0, + result["build_returncode"], + msg=result["build_stdout"] + result["build_stderr"]) def test_tcp_generated_server_builds(self): tcp_iface_dir = os.path.join( diff --git a/open-codegen/test/test_ocp.py b/open-codegen/test/test_ocp.py index 8afdcddd..dc38b27b 100644 --- a/open-codegen/test/test_ocp.py +++ b/open-codegen/test/test_ocp.py @@ -1,5 +1,7 @@ import json import os +import sys +import tempfile import unittest import casadi.casadi as cs @@ -60,7 +62,10 @@ def run(self, p, initial_guess=None, initial_lagrange_multipliers=None, initial_ class OcpTestCase(unittest.TestCase): - TEST_DIR = ".python_test_build_ocp" + if sys.platform == "win32": + TEST_DIR = os.path.join(tempfile.gettempdir(), "og_ocp") + else: + TEST_DIR = ".python_test_build_ocp" @staticmethod def get_open_local_absolute_path():