Skip to content

Commit

Permalink
add impl pointer for ExecutorOptions (#2523)
Browse files Browse the repository at this point in the history
* add impl pointer for ExecutorOptions

Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed May 9, 2024
1 parent 42b0b57 commit 343b29b
Show file tree
Hide file tree
Showing 3 changed files with 75 additions and 5 deletions.
1 change: 1 addition & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/exceptions/exceptions.cpp
src/rclcpp/executable_list.cpp
src/rclcpp/executor.cpp
src/rclcpp/executor_options.cpp
src/rclcpp/executors.cpp
src/rclcpp/executors/executor_entities_collection.cpp
src/rclcpp/executors/executor_entities_collector.cpp
Expand Down
24 changes: 19 additions & 5 deletions rclcpp/include/rclcpp/executor_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#ifndef RCLCPP__EXECUTOR_OPTIONS_HPP_
#define RCLCPP__EXECUTOR_OPTIONS_HPP_

#include <memory>

#include "rclcpp/context.hpp"
#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/memory_strategies.hpp"
Expand All @@ -24,18 +26,30 @@
namespace rclcpp
{

class ExecutorOptionsImplementation;

/// Options to be passed to the executor constructor.
struct ExecutorOptions
{
ExecutorOptions()
: memory_strategy(rclcpp::memory_strategies::create_default_strategy()),
context(rclcpp::contexts::get_global_default_context()),
max_conditions(0)
{}
RCLCPP_PUBLIC
ExecutorOptions();

RCLCPP_PUBLIC
virtual ~ExecutorOptions();

RCLCPP_PUBLIC
ExecutorOptions(const ExecutorOptions &);

RCLCPP_PUBLIC
ExecutorOptions & operator=(const ExecutorOptions &);

rclcpp::memory_strategy::MemoryStrategy::SharedPtr memory_strategy;
rclcpp::Context::SharedPtr context;
size_t max_conditions;

private:
/// Pointer to implementation
std::unique_ptr<ExecutorOptionsImplementation> impl_;
};

} // namespace rclcpp
Expand Down
55 changes: 55 additions & 0 deletions rclcpp/src/rclcpp/executor_options.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
// Copyright 2024 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.

#include "rclcpp/executor_options.hpp"

using rclcpp::ExecutorOptions;

namespace rclcpp
{

class ExecutorOptionsImplementation {};

} // namespace rclcpp

ExecutorOptions::ExecutorOptions()
: memory_strategy(rclcpp::memory_strategies::create_default_strategy()),
context(rclcpp::contexts::get_global_default_context()),
max_conditions(0),
impl_(nullptr)
{}

ExecutorOptions::~ExecutorOptions()
{}

ExecutorOptions::ExecutorOptions(const ExecutorOptions & other)
{
*this = other;
}

ExecutorOptions & ExecutorOptions::operator=(const ExecutorOptions & other)
{
if (this == &other) {
return *this;
}

this->memory_strategy = other.memory_strategy;
this->context = other.context;
this->max_conditions = other.max_conditions;
if (nullptr != other.impl_) {
this->impl_ = std::make_unique<ExecutorOptionsImplementation>(*other.impl_);
}

return *this;
}

0 comments on commit 343b29b

Please sign in to comment.