Skip to content

Commit bf6a673

Browse files
add impl pointer for ExecutorOptions (#2523) (#2525)
* add impl pointer for ExecutorOptions Signed-off-by: William Woodall <william@osrfoundation.org> (cherry picked from commit 343b29b) Co-authored-by: William Woodall <william@osrfoundation.org>
1 parent 4f17dee commit bf6a673

File tree

3 files changed

+75
-5
lines changed

3 files changed

+75
-5
lines changed

rclcpp/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,7 @@ set(${PROJECT_NAME}_SRCS
6363
src/rclcpp/exceptions/exceptions.cpp
6464
src/rclcpp/executable_list.cpp
6565
src/rclcpp/executor.cpp
66+
src/rclcpp/executor_options.cpp
6667
src/rclcpp/executors.cpp
6768
src/rclcpp/executors/executor_entities_collection.cpp
6869
src/rclcpp/executors/executor_entities_collector.cpp

rclcpp/include/rclcpp/executor_options.hpp

Lines changed: 19 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
#ifndef RCLCPP__EXECUTOR_OPTIONS_HPP_
1616
#define RCLCPP__EXECUTOR_OPTIONS_HPP_
1717

18+
#include <memory>
19+
1820
#include "rclcpp/context.hpp"
1921
#include "rclcpp/contexts/default_context.hpp"
2022
#include "rclcpp/memory_strategies.hpp"
@@ -24,18 +26,30 @@
2426
namespace rclcpp
2527
{
2628

29+
class ExecutorOptionsImplementation;
30+
2731
/// Options to be passed to the executor constructor.
2832
struct ExecutorOptions
2933
{
30-
ExecutorOptions()
31-
: memory_strategy(rclcpp::memory_strategies::create_default_strategy()),
32-
context(rclcpp::contexts::get_global_default_context()),
33-
max_conditions(0)
34-
{}
34+
RCLCPP_PUBLIC
35+
ExecutorOptions();
36+
37+
RCLCPP_PUBLIC
38+
virtual ~ExecutorOptions();
39+
40+
RCLCPP_PUBLIC
41+
ExecutorOptions(const ExecutorOptions &);
42+
43+
RCLCPP_PUBLIC
44+
ExecutorOptions & operator=(const ExecutorOptions &);
3545

3646
rclcpp::memory_strategy::MemoryStrategy::SharedPtr memory_strategy;
3747
rclcpp::Context::SharedPtr context;
3848
size_t max_conditions;
49+
50+
private:
51+
/// Pointer to implementation
52+
std::unique_ptr<ExecutorOptionsImplementation> impl_;
3953
};
4054

4155
} // namespace rclcpp
Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
// Copyright 2024 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "rclcpp/executor_options.hpp"
16+
17+
using rclcpp::ExecutorOptions;
18+
19+
namespace rclcpp
20+
{
21+
22+
class ExecutorOptionsImplementation {};
23+
24+
} // namespace rclcpp
25+
26+
ExecutorOptions::ExecutorOptions()
27+
: memory_strategy(rclcpp::memory_strategies::create_default_strategy()),
28+
context(rclcpp::contexts::get_global_default_context()),
29+
max_conditions(0),
30+
impl_(nullptr)
31+
{}
32+
33+
ExecutorOptions::~ExecutorOptions()
34+
{}
35+
36+
ExecutorOptions::ExecutorOptions(const ExecutorOptions & other)
37+
{
38+
*this = other;
39+
}
40+
41+
ExecutorOptions & ExecutorOptions::operator=(const ExecutorOptions & other)
42+
{
43+
if (this == &other) {
44+
return *this;
45+
}
46+
47+
this->memory_strategy = other.memory_strategy;
48+
this->context = other.context;
49+
this->max_conditions = other.max_conditions;
50+
if (nullptr != other.impl_) {
51+
this->impl_ = std::make_unique<ExecutorOptionsImplementation>(*other.impl_);
52+
}
53+
54+
return *this;
55+
}

0 commit comments

Comments
 (0)