diff --git a/rclpy/src/rclpy/clock_event.cpp b/rclpy/src/rclpy/clock_event.cpp index 71056dee3..34cb0f0e2 100644 --- a/rclpy/src/rclpy/clock_event.cpp +++ b/rclpy/src/rclpy/clock_event.cpp @@ -23,6 +23,7 @@ #include #include "clock_event.hpp" +#include "gil_utils.hpp" namespace py = pybind11; @@ -48,7 +49,7 @@ void ClockEvent::wait_until(std::shared_ptr clock, rcl_time_point_t until std::chrono::nanoseconds(delta_t.nanoseconds)); // Could be a long wait, release the gil - py::gil_scoped_release release; + gil_scoped_release release; std::unique_lock lock(mutex_); cv_.wait_until(lock, chrono_until, [this]() {return state_;}); } @@ -58,7 +59,7 @@ void ClockEvent::wait_until_ros(std::shared_ptr clock, rcl_time_point_t u // Check if ROS time is enabled in C++ to avoid TOCTTOU with TimeSource by holding GIL if (clock->get_ros_time_override_is_enabled()) { // Could be a long wait, release the gil - py::gil_scoped_release release; + gil_scoped_release release; std::unique_lock lock(mutex_); // Caller must have setup a time jump callback to wake this event cv_.wait(lock, [this]() {return state_;}); diff --git a/rclpy/src/rclpy/events_executor/events_executor.cpp b/rclpy/src/rclpy/events_executor/events_executor.cpp index 0087a79b6..63090137c 100644 --- a/rclpy/src/rclpy/events_executor/events_executor.cpp +++ b/rclpy/src/rclpy/events_executor/events_executor.cpp @@ -36,6 +36,7 @@ #include "client.hpp" #include "context.hpp" +#include "gil_utils.hpp" #include "service.hpp" #include "subscription.hpp" @@ -95,7 +96,7 @@ bool EventsExecutor::shutdown(std::optional timeout) // Block until spinning is done, or timeout. Release the GIL while we block though. { - py::gil_scoped_release gil_release; + gil_scoped_release gil_release; std::unique_lock spin_lock(spinning_mutex_, std::defer_lock); if (timeout) { if (!spin_lock.try_lock_for(std::chrono::duration(*timeout))) { @@ -168,7 +169,7 @@ void EventsExecutor::spin(std::optional timeout_sec, bool stop_after_use PostOutstandingTasks(); // Release the GIL while we block. Any callbacks on the events queue that want to touch Python // will need to reacquire it though. - py::gil_scoped_release gil_release; + gil_scoped_release gil_release; if (timeout_sec) { const auto timeout_ns = std::chrono::duration_cast( std::chrono::duration(*timeout_sec)); diff --git a/rclpy/src/rclpy/gil_utils.hpp b/rclpy/src/rclpy/gil_utils.hpp new file mode 100644 index 000000000..f1b386010 --- /dev/null +++ b/rclpy/src/rclpy/gil_utils.hpp @@ -0,0 +1,48 @@ +// Copyright 2025 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RCLPY__GIL_UTILS_HPP_ +#define RCLPY__GIL_UTILS_HPP_ + +#include + +#if PY_VERSION_HEX < Py_PACK_FULL_VERSION(3, 13)) +#define rclpy_IsPythonFinalizing _Py_IsFinalizing +#else +#define rclpy_IsPythonFinalizing Py_IsFinalizing +#endif + +namespace rclpy +{ + +class gil_scoped_release +{ +public: + gil_scoped_release() = default; + + ~gil_scoped_release() { + // Avoid taking the GIL if runtime is finalizing + if (rclpy_IsPythonFinalizing()) { + gil_release_.disarm(); + } + } + +private: + + pybind11::gil_scoped_release gil_release_; +}; + +} // namespace rclpy + +#endif // RCLPY__GIL_UTILS_HPP_ diff --git a/rclpy/src/rclpy/wait_set.cpp b/rclpy/src/rclpy/wait_set.cpp index d82461dae..4e932ff1c 100644 --- a/rclpy/src/rclpy/wait_set.cpp +++ b/rclpy/src/rclpy/wait_set.cpp @@ -24,6 +24,7 @@ #include #include "exceptions.hpp" +#include "gil_utils.hpp" #include "wait_set.hpp" namespace rclpy @@ -243,7 +244,7 @@ WaitSet::wait(int64_t timeout) // Could be a long wait, release the GIL { - py::gil_scoped_release gil_release; + gil_scoped_release gil_release; ret = rcl_wait(rcl_wait_set_.get(), timeout); }