Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use windows CI build #204

Merged
merged 11 commits into from
Nov 25, 2024
29 changes: 29 additions & 0 deletions .github/workflows/binary-build-win.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
name: Windows Binary Build
# author: Christoph Fröhlich <[email protected]>
# description: 'Build & test all dependencies from released (binary) windows packages.'

on:
workflow_dispatch:
pull_request:
branches:
- master
# types:
# - labeled
push:
branches:
- master
# issue_comment:
# types:
# - created

jobs:
binary-windows:
# if: |
# (github.event_name == 'issue_comment' && contains(github.event.comment.body, '/check-windows')) ||
# (github.event_name == 'pull_request' && contains(github.event.label.name, 'check-windows')) ||
# (github.event_name == 'workflow_dispatch')
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-ros-tooling-win-build.yml@master
with:
ros_distro: jazzy
ref_for_scheduled_build: master
os_name: windows-2019
12 changes: 12 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,18 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
-Werror=return-type -Werror=shadow -Werror=format)
endif()

if(WIN32)
add_compile_definitions(
# For math constants
_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
rclcpp
rclcpp_action
Expand Down
5 changes: 4 additions & 1 deletion test/realtime_box_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,10 @@
// POSSIBILITY OF SUCH DAMAGE.

#include <gmock/gmock.h>
#include <realtime_tools/realtime_box.h>

#include <array>

#include "realtime_tools/realtime_box.h"

struct DefaultConstructable
{
Expand Down
12 changes: 7 additions & 5 deletions test/test_async_function_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -303,9 +303,9 @@ TEST_F(AsyncFunctionHandlerTest, check_triggering_with_different_return_state_an
ASSERT_FALSE(async_class.get_handler().is_trigger_cycle_in_progress());
ASSERT_EQ(async_class.get_counter(), 1);

// Trigger one more cycle to return ERROR at the end of cycle,
// Trigger one more cycle to return FAILURE at the end of cycle,
// so return from this cycle should be last cycle's return
async_class.set_return_state(realtime_tools::return_type::ERROR);
async_class.set_return_state(realtime_tools::return_type::FAILURE);
trigger_status = async_class.trigger();
ASSERT_TRUE(trigger_status.first);
ASSERT_EQ(realtime_tools::return_type::OK, trigger_status.second);
Expand All @@ -316,20 +316,22 @@ TEST_F(AsyncFunctionHandlerTest, check_triggering_with_different_return_state_an
ASSERT_EQ(async_class.get_handler().get_last_return_value(), realtime_tools::return_type::OK);
async_class.get_handler().wait_for_trigger_cycle_to_finish();
ASSERT_FALSE(async_class.get_handler().is_trigger_cycle_in_progress());
ASSERT_EQ(async_class.get_handler().get_last_return_value(), realtime_tools::return_type::ERROR);
ASSERT_EQ(
async_class.get_handler().get_last_return_value(), realtime_tools::return_type::FAILURE);
ASSERT_LE(async_class.get_counter(), 2);

// Trigger one more cycle to return DEACTIVATE at the end of cycle,
async_class.set_return_state(realtime_tools::return_type::DEACTIVATE);
trigger_status = async_class.trigger();
ASSERT_TRUE(trigger_status.first);
ASSERT_EQ(realtime_tools::return_type::ERROR, trigger_status.second);
ASSERT_EQ(realtime_tools::return_type::FAILURE, trigger_status.second);
ASSERT_TRUE(async_class.get_handler().is_initialized());
ASSERT_TRUE(async_class.get_handler().is_running());
ASSERT_FALSE(async_class.get_handler().is_stopped());
ASSERT_FALSE(async_class.get_handler().is_stopped());
ASSERT_TRUE(async_class.get_handler().is_trigger_cycle_in_progress());
ASSERT_EQ(async_class.get_handler().get_last_return_value(), realtime_tools::return_type::ERROR);
ASSERT_EQ(
async_class.get_handler().get_last_return_value(), realtime_tools::return_type::FAILURE);
async_class.get_handler().wait_for_trigger_cycle_to_finish();
ASSERT_FALSE(async_class.get_handler().is_trigger_cycle_in_progress());
ASSERT_EQ(
Expand Down
2 changes: 1 addition & 1 deletion test/test_async_function_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace realtime_tools
{
enum class return_type : std::uint8_t {
OK = 0,
ERROR = 1,
FAILURE = 1,
DEACTIVATE = 2,
};

Expand Down
Loading