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 rcpputils/scope_exit.hpp and remove rclcpp/scope_exit.hpp #1727

Merged
merged 4 commits into from
Jul 26, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@

#include "rcl/guard_condition.h"
#include "rcl/wait.h"
#include "rcpputils/scope_exit.hpp"

#include "rclcpp/context.hpp"
#include "rclcpp/contexts/default_context.hpp"
Expand All @@ -40,7 +41,6 @@
#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rclcpp/scope_exit.hpp"

namespace rclcpp
{
Expand Down Expand Up @@ -354,7 +354,7 @@ class Executor
if (spinning.exchange(true)) {
throw std::runtime_error("spin_until_future_complete() called while already spinning");
}
RCLCPP_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
while (rclcpp::ok(this->context_) && spinning.load()) {
// Do one item of work.
spin_once_impl(timeout_left);
Expand Down
1 change: 0 additions & 1 deletion rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,6 @@
* - rclcpp/duration.hpp
* - rclcpp/function_traits.hpp
* - rclcpp/macros.hpp
* - rclcpp/scope_exit.hpp
* - rclcpp/time.hpp
* - rclcpp/utilities.hpp
* - rclcpp/typesupport_helpers.hpp
Expand Down
4 changes: 4 additions & 0 deletions rclcpp/include/rclcpp/scope_exit.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,10 @@
#ifndef RCLCPP__SCOPE_EXIT_HPP_
#define RCLCPP__SCOPE_EXIT_HPP_

// TODO(christophebedard) remove this header completely in I-turtle

#warning rclcpp/scope_exit.hpp has been deprecated, please use rcpputils/scope_exit.hpp instead

#include <functional>

#include "rclcpp/macros.hpp"
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/wait_set_template.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,13 +20,13 @@
#include <utility>

#include "rcl/wait.h"
#include "rcpputils/scope_exit.hpp"

#include "rclcpp/client.hpp"
#include "rclcpp/context.hpp"
#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/guard_condition.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/scope_exit.hpp"
#include "rclcpp/service.hpp"
#include "rclcpp/subscription_base.hpp"
#include "rclcpp/subscription_wait_set_mask.hpp"
Expand Down Expand Up @@ -657,7 +657,7 @@ class WaitSetTemplate final : private SynchronizationPolicy, private StoragePoli

// ensure the ownership of the entities in the wait set is shared for the duration of wait
this->storage_acquire_ownerships();
RCLCPP_SCOPE_EXIT({this->storage_release_ownerships();});
RCPPUTILS_SCOPE_EXIT({this->storage_release_ownerships();});

// this method comes from the SynchronizationPolicy
return this->template sync_wait<WaitResult<WaitSetTemplate>>(
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/detail/resolve_parameter_overrides.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@
#include <vector>

#include "rcl_yaml_param_parser/parser.h"
#include "rcpputils/scope_exit.hpp"

#include "rclcpp/scope_exit.hpp"
#include "rclcpp/parameter_map.hpp"

std::map<std::string, rclcpp::ParameterValue>
Expand All @@ -47,7 +47,7 @@ rclcpp::detail::resolve_parameter_overrides(
rclcpp::exceptions::throw_from_rcl_error(ret);
}
if (params) {
auto cleanup_params = make_scope_exit(
auto cleanup_params = rcpputils::make_scope_exit(
[params]() {
rcl_yaml_node_struct_fini(params);
});
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,13 @@

#include "rcl/allocator.h"
#include "rcl/error_handling.h"
#include "rcpputils/scope_exit.hpp"

#include "rclcpp/exceptions.hpp"
#include "rclcpp/executor.hpp"
#include "rclcpp/guard_condition.hpp"
#include "rclcpp/memory_strategy.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/scope_exit.hpp"
#include "rclcpp/utilities.hpp"

#include "rcutils/logging_macros.h"
Expand Down Expand Up @@ -450,7 +450,7 @@ Executor::spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive)
if (spinning.exchange(true)) {
throw std::runtime_error("spin_some() called while already spinning");
}
RCLCPP_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
bool work_available = false;
while (rclcpp::ok(context_) && spinning.load() && max_duration_not_elapsed()) {
AnyExecutable any_exec;
Expand Down Expand Up @@ -484,7 +484,7 @@ Executor::spin_once(std::chrono::nanoseconds timeout)
if (spinning.exchange(true)) {
throw std::runtime_error("spin_once() called while already spinning");
}
RCLCPP_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
spin_once_impl(timeout);
}

Expand Down
5 changes: 3 additions & 2 deletions rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,9 @@
#include <memory>
#include <vector>

#include "rcpputils/scope_exit.hpp"

#include "rclcpp/utilities.hpp"
#include "rclcpp/scope_exit.hpp"

using rclcpp::detail::MutexTwoPriorities;
using rclcpp::executors::MultiThreadedExecutor;
Expand Down Expand Up @@ -48,7 +49,7 @@ MultiThreadedExecutor::spin()
if (spinning.exchange(true)) {
throw std::runtime_error("spin() called while already spinning");
}
RCLCPP_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
std::vector<std::thread> threads;
size_t thread_id = 0;
{
Expand Down
5 changes: 3 additions & 2 deletions rclcpp/src/rclcpp/executors/single_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "rcpputils/scope_exit.hpp"

#include "rclcpp/executors/single_threaded_executor.hpp"
#include "rclcpp/any_executable.hpp"
#include "rclcpp/scope_exit.hpp"

using rclcpp::executors::SingleThreadedExecutor;

Expand All @@ -29,7 +30,7 @@ SingleThreadedExecutor::spin()
if (spinning.exchange(true)) {
throw std::runtime_error("spin() called while already spinning");
}
RCLCPP_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
while (rclcpp::ok(this->context_) && spinning.load()) {
rclcpp::AnyExecutable any_executable;
if (get_next_executable(any_executable)) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <memory>
#include <vector>

#include "rclcpp/scope_exit.hpp"
#include "rcpputils/scope_exit.hpp"

using rclcpp::executors::StaticSingleThreadedExecutor;
using rclcpp::experimental::ExecutableList;
Expand All @@ -43,7 +43,7 @@ StaticSingleThreadedExecutor::spin()
if (spinning.exchange(true)) {
throw std::runtime_error("spin() called while already spinning");
}
RCLCPP_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );

// Set memory_strategy_ and exec_list_ based on weak_nodes_
// Prepare wait_set_ based on memory_strategy_
Expand Down Expand Up @@ -100,7 +100,7 @@ StaticSingleThreadedExecutor::spin_some_impl(std::chrono::nanoseconds max_durati
if (spinning.exchange(true)) {
throw std::runtime_error("spin_some() called while already spinning");
}
RCLCPP_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );

while (rclcpp::ok(context_) && spinning.load() && max_duration_not_elapsed()) {
// Get executables that are ready now
Expand Down
1 change: 0 additions & 1 deletion rclcpp/src/rclcpp/expand_topic_or_service_name.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include "rcl/expand_topic_name.h"
#include "rcl/validate_topic_name.h"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/scope_exit.hpp"
#include "rcutils/logging_macros.h"
#include "rcutils/types/string_map.h"
#include "rmw/error_handling.h"
Expand Down
1 change: 0 additions & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@
#include "rcl_interfaces/srv/list_parameters.hpp"
#include "rclcpp/create_publisher.hpp"
#include "rclcpp/parameter_map.hpp"
#include "rclcpp/scope_exit.hpp"
#include "rcutils/logging_macros.h"
#include "rmw/qos_profiles.h"

Expand Down
6 changes: 3 additions & 3 deletions rclcpp/test/benchmark/benchmark_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include "performance_test_fixture/performance_test_fixture.hpp"

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/scope_exit.hpp"
#include "rcpputils/scope_exit.hpp"
#include "test_msgs/msg/empty.hpp"

using namespace std::chrono_literals;
Expand Down Expand Up @@ -366,7 +366,7 @@ BENCHMARK_F(
if (ret != RCL_RET_OK) {
st.SkipWithError(rcutils_get_error_string().str);
}
RCLCPP_SCOPE_EXIT(
RCPPUTILS_SCOPE_EXIT(
{
rcl_ret_t ret = rcl_wait_set_fini(&wait_set);
if (ret != RCL_RET_OK) {
Expand All @@ -379,7 +379,7 @@ BENCHMARK_F(
rcl_guard_condition_t rcl_guard_condition = guard_condition.get_rcl_guard_condition();

entities_collector_->init(&wait_set, memory_strategy, &rcl_guard_condition);
RCLCPP_SCOPE_EXIT(entities_collector_->fini());
RCPPUTILS_SCOPE_EXIT(entities_collector_->fini());

reset_heap_counters();

Expand Down
Loading