Program Listing for File node_options.hpp
↰ Return to documentation for file (include/rclcpp/node_options.hpp
)
// Copyright 2019 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 RCLCPP__NODE_OPTIONS_HPP_
#define RCLCPP__NODE_OPTIONS_HPP_
#include <memory>
#include <string>
#include <vector>
#include "rcl/node_options.h"
#include "rclcpp/context.hpp"
#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/publisher_options.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
{
class NodeOptions
{
public:
RCLCPP_PUBLIC
explicit NodeOptions(rcl_allocator_t allocator = rcl_get_default_allocator());
RCLCPP_PUBLIC
virtual
~NodeOptions() = default;
RCLCPP_PUBLIC
NodeOptions(const NodeOptions & other);
RCLCPP_PUBLIC
NodeOptions &
operator=(const NodeOptions & other);
RCLCPP_PUBLIC
const rcl_node_options_t *
get_rcl_node_options() const;
RCLCPP_PUBLIC
rclcpp::Context::SharedPtr
context() const;
RCLCPP_PUBLIC
NodeOptions &
context(rclcpp::Context::SharedPtr context);
RCLCPP_PUBLIC
const std::vector<std::string> &
arguments() const;
RCLCPP_PUBLIC
NodeOptions &
arguments(const std::vector<std::string> & arguments);
RCLCPP_PUBLIC
std::vector<rclcpp::Parameter> &
parameter_overrides();
RCLCPP_PUBLIC
const std::vector<rclcpp::Parameter> &
parameter_overrides() const;
RCLCPP_PUBLIC
NodeOptions &
parameter_overrides(const std::vector<rclcpp::Parameter> & parameter_overrides);
template<typename ParameterT>
NodeOptions &
append_parameter_override(const std::string & name, const ParameterT & value)
{
this->parameter_overrides().emplace_back(name, rclcpp::ParameterValue(value));
return *this;
}
RCLCPP_PUBLIC
bool
use_global_arguments() const;
RCLCPP_PUBLIC
NodeOptions &
use_global_arguments(bool use_global_arguments);
RCLCPP_PUBLIC
bool
enable_rosout() const;
RCLCPP_PUBLIC
NodeOptions &
enable_rosout(bool enable_rosout);
RCLCPP_PUBLIC
bool
use_intra_process_comms() const;
RCLCPP_PUBLIC
NodeOptions &
use_intra_process_comms(bool use_intra_process_comms);
RCLCPP_PUBLIC
bool
enable_topic_statistics() const;
RCLCPP_PUBLIC
NodeOptions &
enable_topic_statistics(bool enable_topic_statistics);
RCLCPP_PUBLIC
bool
start_parameter_services() const;
RCLCPP_PUBLIC
NodeOptions &
start_parameter_services(bool start_parameter_services);
RCLCPP_PUBLIC
bool
start_parameter_event_publisher() const;
RCLCPP_PUBLIC
NodeOptions &
start_parameter_event_publisher(bool start_parameter_event_publisher);
RCLCPP_PUBLIC
const rclcpp::QoS &
clock_qos() const;
RCLCPP_PUBLIC
NodeOptions &
clock_qos(const rclcpp::QoS & clock_qos);
RCLCPP_PUBLIC
bool
use_clock_thread() const;
RCLCPP_PUBLIC
NodeOptions &
use_clock_thread(bool use_clock_thread);
RCLCPP_PUBLIC
const rclcpp::QoS &
parameter_event_qos() const;
RCLCPP_PUBLIC
NodeOptions &
parameter_event_qos(const rclcpp::QoS & parameter_event_qos);
RCLCPP_PUBLIC
const rclcpp::QoS &
rosout_qos() const;
RCLCPP_PUBLIC
NodeOptions &
rosout_qos(const rclcpp::QoS & rosout_qos);
RCLCPP_PUBLIC
const rclcpp::PublisherOptionsBase &
parameter_event_publisher_options() const;
RCLCPP_PUBLIC
NodeOptions &
parameter_event_publisher_options(
const rclcpp::PublisherOptionsBase & parameter_event_publisher_options);
RCLCPP_PUBLIC
bool
allow_undeclared_parameters() const;
RCLCPP_PUBLIC
NodeOptions &
allow_undeclared_parameters(bool allow_undeclared_parameters);
RCLCPP_PUBLIC
bool
automatically_declare_parameters_from_overrides() const;
RCLCPP_PUBLIC
NodeOptions &
automatically_declare_parameters_from_overrides(
bool automatically_declare_parameters_from_overrides);
RCLCPP_PUBLIC
const rcl_allocator_t &
allocator() const;
RCLCPP_PUBLIC
NodeOptions &
allocator(rcl_allocator_t allocator);
private:
// This is mutable to allow for a const accessor which lazily creates the node options instance.
mutable std::unique_ptr<rcl_node_options_t, void (*)(rcl_node_options_t *)> node_options_;
// IMPORTANT: if any of these default values are changed, please update the
// documentation in this class.
rclcpp::Context::SharedPtr context_ {
rclcpp::contexts::get_global_default_context()};
std::vector<std::string> arguments_ {};
std::vector<rclcpp::Parameter> parameter_overrides_ {};
bool use_global_arguments_ {true};
bool enable_rosout_ {true};
bool use_intra_process_comms_ {false};
bool enable_topic_statistics_ {false};
bool start_parameter_services_ {true};
bool start_parameter_event_publisher_ {true};
rclcpp::QoS clock_qos_ = rclcpp::ClockQoS();
bool use_clock_thread_ {true};
rclcpp::QoS parameter_event_qos_ = rclcpp::ParameterEventsQoS(
rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
);
rclcpp::QoS rosout_qos_ = rclcpp::RosoutQoS();
rclcpp::PublisherOptionsBase parameter_event_publisher_options_ = rclcpp::PublisherOptionsBase();
bool allow_undeclared_parameters_ {false};
bool automatically_declare_parameters_from_overrides_ {false};
rcl_allocator_t allocator_ {rcl_get_default_allocator()};
};
} // namespace rclcpp
#endif // RCLCPP__NODE_OPTIONS_HPP_