Replace node constructor arguments with NodeOptions (#622)
* Start work on creaating NodeOptions structure. Signed-off-by: Michael Carroll <michael@openrobotics.org> * Continue work on NodeOptions. Signed-off-by: Michael Carroll <michael@openrobotics.org> * Update tests for NodeOptions impl. Signed-off-by: Michael Carroll <michael@openrobotics.org> * Update documentation and copy/assignment. Signed-off-by: Michael Carroll <michael@openrobotics.org> * Update rclcpp_lifecycle to conform to new API. Signed-off-by: Michael Carroll <michael@openrobotics.org> * Use builder pattern with NodeOptions. Signed-off-by: Michael Carroll <michael@openrobotics.org> * Documentation updates. Signed-off-by: Michael Carroll <michael@openrobotics.org> * Update rclcpp_lifecycle to use NodeOptions. Signed-off-by: Michael Carroll <michael@openrobotics.org> * change to parameter idiom only, from builder pattern Signed-off-by: William Woodall <william@osrfoundation.org> * Update rclcpp/include/rclcpp/node_options.hpp Co-Authored-By: wjwwood <william+github@osrfoundation.org> Signed-off-by: William Woodall <william@osrfoundation.org> * follow up with more resets of the rcl_node_options_t Signed-off-by: William Woodall <william@osrfoundation.org> * todo about get env Signed-off-by: William Woodall <william@osrfoundation.org>
This commit is contained in:
parent
c7ac39a0e6
commit
0f9098e9b6
11 changed files with 506 additions and 194 deletions
|
@ -47,6 +47,7 @@ set(${PROJECT_NAME}_SRCS
|
||||||
src/rclcpp/memory_strategies.cpp
|
src/rclcpp/memory_strategies.cpp
|
||||||
src/rclcpp/memory_strategy.cpp
|
src/rclcpp/memory_strategy.cpp
|
||||||
src/rclcpp/node.cpp
|
src/rclcpp/node.cpp
|
||||||
|
src/rclcpp/node_options.cpp
|
||||||
src/rclcpp/node_interfaces/node_base.cpp
|
src/rclcpp/node_interfaces/node_base.cpp
|
||||||
src/rclcpp/node_interfaces/node_clock.cpp
|
src/rclcpp/node_interfaces/node_clock.cpp
|
||||||
src/rclcpp/node_interfaces/node_graph.cpp
|
src/rclcpp/node_interfaces/node_graph.cpp
|
||||||
|
|
|
@ -41,6 +41,7 @@
|
||||||
#include "rclcpp/logger.hpp"
|
#include "rclcpp/logger.hpp"
|
||||||
#include "rclcpp/macros.hpp"
|
#include "rclcpp/macros.hpp"
|
||||||
#include "rclcpp/message_memory_strategy.hpp"
|
#include "rclcpp/message_memory_strategy.hpp"
|
||||||
|
#include "rclcpp/node_options.hpp"
|
||||||
#include "rclcpp/node_interfaces/node_base_interface.hpp"
|
#include "rclcpp/node_interfaces/node_base_interface.hpp"
|
||||||
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
|
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
|
||||||
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
|
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
|
||||||
|
@ -72,40 +73,24 @@ public:
|
||||||
/// Create a new node with the specified name.
|
/// Create a new node with the specified name.
|
||||||
/**
|
/**
|
||||||
* \param[in] node_name Name of the node.
|
* \param[in] node_name Name of the node.
|
||||||
* \param[in] namespace_ Namespace of the node.
|
* \param[in] options Additional options to control creation of the node.
|
||||||
* \param[in] use_intra_process_comms True to use the optimized intra-process communication
|
|
||||||
* pipeline to pass messages between nodes in the same process using shared memory.
|
|
||||||
*/
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
explicit Node(
|
explicit Node(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
const std::string & namespace_ = "",
|
const NodeOptions & options = NodeOptions());
|
||||||
bool use_intra_process_comms = false);
|
|
||||||
|
|
||||||
/// Create a node based on the node name and a rclcpp::Context.
|
/// Create a new node with the specified name.
|
||||||
/**
|
/**
|
||||||
* \param[in] node_name Name of the node.
|
* \param[in] node_name Name of the node.
|
||||||
* \param[in] namespace_ Namespace of the node.
|
* \param[in] namespace_ Namespace of the node.
|
||||||
* \param[in] context The context for the node (usually represents the state of a process).
|
* \param[in] options Additional options to control creation of the node.
|
||||||
* \param[in] arguments Command line arguments that should apply only to this node.
|
|
||||||
* \param[in] initial_parameters a list of initial values for parameters on the node.
|
|
||||||
* This can be used to provide remapping rules that only affect one instance.
|
|
||||||
* \param[in] use_global_arguments False to prevent node using arguments passed to the process.
|
|
||||||
* \param[in] use_intra_process_comms True to use the optimized intra-process communication
|
|
||||||
* pipeline to pass messages between nodes in the same process using shared memory.
|
|
||||||
* \param[in] start_parameter_services True to setup ROS interfaces for accessing parameters
|
|
||||||
* in the node.
|
|
||||||
*/
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
Node(
|
explicit Node(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
const std::string & namespace_,
|
const std::string & namespace_,
|
||||||
rclcpp::Context::SharedPtr context,
|
const NodeOptions & options = NodeOptions());
|
||||||
const std::vector<std::string> & arguments,
|
|
||||||
const std::vector<Parameter> & initial_parameters,
|
|
||||||
bool use_global_arguments = true,
|
|
||||||
bool use_intra_process_comms = false,
|
|
||||||
bool start_parameter_services = true);
|
|
||||||
|
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
virtual ~Node();
|
virtual ~Node();
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
|
|
||||||
#include "rclcpp/context.hpp"
|
#include "rclcpp/context.hpp"
|
||||||
#include "rclcpp/macros.hpp"
|
#include "rclcpp/macros.hpp"
|
||||||
|
#include "rclcpp/node_options.hpp"
|
||||||
#include "rclcpp/node_interfaces/node_base_interface.hpp"
|
#include "rclcpp/node_interfaces/node_base_interface.hpp"
|
||||||
#include "rclcpp/visibility_control.hpp"
|
#include "rclcpp/visibility_control.hpp"
|
||||||
|
|
||||||
|
@ -39,9 +40,7 @@ public:
|
||||||
NodeBase(
|
NodeBase(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
const std::string & namespace_,
|
const std::string & namespace_,
|
||||||
rclcpp::Context::SharedPtr context,
|
const NodeOptions & options);
|
||||||
const std::vector<std::string> & arguments,
|
|
||||||
bool use_global_arguments);
|
|
||||||
|
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
virtual
|
virtual
|
||||||
|
|
199
rclcpp/include/rclcpp/node_options.hpp
Normal file
199
rclcpp/include/rclcpp/node_options.hpp
Normal file
|
@ -0,0 +1,199 @@
|
||||||
|
// 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/visibility_control.hpp"
|
||||||
|
|
||||||
|
namespace rclcpp
|
||||||
|
{
|
||||||
|
|
||||||
|
/// Encapsulation of options for node initialization.
|
||||||
|
class NodeOptions
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
/// Create NodeOptions with default values, optionally specifying the allocator to use.
|
||||||
|
/**
|
||||||
|
* Default values for the node options:
|
||||||
|
*
|
||||||
|
* - context = rclcpp::contexts::default_context::get_global_default_context()
|
||||||
|
* - arguments = {}
|
||||||
|
* - initial_parameters = {}
|
||||||
|
* - use_global_arguments = true
|
||||||
|
* - use_intra_process_comms = false
|
||||||
|
* - start_parameter_services = true
|
||||||
|
* - allocator = rcl_get_default_allocator()
|
||||||
|
*
|
||||||
|
* \param[in] allocator allocator to use in construction of NodeOptions.
|
||||||
|
*/
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
explicit NodeOptions(rcl_allocator_t allocator = rcl_get_default_allocator());
|
||||||
|
|
||||||
|
/// Destructor.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
virtual
|
||||||
|
~NodeOptions() = default;
|
||||||
|
|
||||||
|
/// Copy constructor.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
NodeOptions(const NodeOptions & other);
|
||||||
|
|
||||||
|
/// Assignment operator.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
NodeOptions &
|
||||||
|
operator=(const NodeOptions & other);
|
||||||
|
|
||||||
|
/// Return the rcl_node_options used by the node.
|
||||||
|
/**
|
||||||
|
* This data structure is created lazily, on the first call to this function.
|
||||||
|
* Repeated calls will not regenerate it unless one of the input settings
|
||||||
|
* changed, like arguments, use_global_arguments, or the rcl allocator.
|
||||||
|
*/
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
const rcl_node_options_t *
|
||||||
|
get_rcl_node_options() const;
|
||||||
|
|
||||||
|
/// Return the context to be used by the node.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
rclcpp::Context::SharedPtr
|
||||||
|
context() const;
|
||||||
|
|
||||||
|
/// Set the context, return this for parameter idiom.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
NodeOptions &
|
||||||
|
context(rclcpp::Context::SharedPtr context);
|
||||||
|
|
||||||
|
/// Return a reference to the list of arguments for the node.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
const std::vector<std::string> &
|
||||||
|
arguments() const;
|
||||||
|
|
||||||
|
/// Set the arguments, return this for parameter idiom.
|
||||||
|
/**
|
||||||
|
* This will cause the internal rcl_node_options_t struct to be invalidated.
|
||||||
|
*/
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
NodeOptions &
|
||||||
|
arguments(const std::vector<std::string> & arguments);
|
||||||
|
|
||||||
|
/// Return a reference to the list of initial parameters.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
std::vector<rclcpp::Parameter> &
|
||||||
|
initial_parameters();
|
||||||
|
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
const std::vector<rclcpp::Parameter> &
|
||||||
|
initial_parameters() const;
|
||||||
|
|
||||||
|
/// Set the initial parameters, return this for parameter idiom.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
NodeOptions &
|
||||||
|
initial_parameters(const std::vector<rclcpp::Parameter> & initial_parameters);
|
||||||
|
|
||||||
|
/// Append a single initial parameter, parameter idiom style.
|
||||||
|
template<typename ParameterT>
|
||||||
|
NodeOptions &
|
||||||
|
append_initial_parameter(const std::string & name, const ParameterT & value)
|
||||||
|
{
|
||||||
|
this->initial_parameters().emplace_back(name, rclcpp::ParameterValue(value));
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Return a reference to the use_global_arguments flag.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
const bool &
|
||||||
|
use_global_arguments() const;
|
||||||
|
|
||||||
|
/// Set the use_global_arguments flag, return this for parameter idiom.
|
||||||
|
/**
|
||||||
|
* This will cause the internal rcl_node_options_t struct to be invalidated.
|
||||||
|
*/
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
NodeOptions &
|
||||||
|
use_global_arguments(const bool & use_global_arguments);
|
||||||
|
|
||||||
|
/// Return a reference to the use_intra_process_comms flag
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
const bool &
|
||||||
|
use_intra_process_comms() const;
|
||||||
|
|
||||||
|
/// Set the use_intra_process_comms flag, return this for parameter idiom.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
NodeOptions &
|
||||||
|
use_intra_process_comms(const bool & use_intra_process_comms);
|
||||||
|
|
||||||
|
/// Return a reference to the start_parameter_services flag
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
const bool &
|
||||||
|
start_parameter_services() const;
|
||||||
|
|
||||||
|
/// Set the start_parameter_services flag, return this for parameter idiom.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
NodeOptions &
|
||||||
|
start_parameter_services(const bool & start_parameter_services);
|
||||||
|
|
||||||
|
/// Return the rcl_allocator_t to be used.
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
const rcl_allocator_t &
|
||||||
|
allocator() const;
|
||||||
|
|
||||||
|
/// Set the rcl_allocator_t to be used, may cause deallocation of existing rcl_node_options_t.
|
||||||
|
/**
|
||||||
|
* This will cause the internal rcl_node_options_t struct to be invalidated.
|
||||||
|
*/
|
||||||
|
RCLCPP_PUBLIC
|
||||||
|
NodeOptions &
|
||||||
|
allocator(rcl_allocator_t allocator);
|
||||||
|
|
||||||
|
protected:
|
||||||
|
/// Retrieve the ROS_DOMAIN_ID environment variable and populate options.
|
||||||
|
size_t
|
||||||
|
get_domain_id_from_env() const;
|
||||||
|
|
||||||
|
private:
|
||||||
|
// This is mutable to allow for a const accessor which lazily creates the node options instance.
|
||||||
|
/// Underlying rcl_node_options structure.
|
||||||
|
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::default_context::get_global_default_context()};
|
||||||
|
|
||||||
|
std::vector<std::string> arguments_ {};
|
||||||
|
|
||||||
|
std::vector<rclcpp::Parameter> initial_parameters_ {};
|
||||||
|
|
||||||
|
bool use_global_arguments_ {true};
|
||||||
|
|
||||||
|
bool use_intra_process_comms_ {false};
|
||||||
|
|
||||||
|
bool start_parameter_services_ {true};
|
||||||
|
|
||||||
|
rcl_allocator_t allocator_ {rcl_get_default_allocator()};
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace rclcpp
|
||||||
|
|
||||||
|
#endif // RCLCPP__NODE_OPTIONS_HPP_
|
|
@ -35,34 +35,22 @@
|
||||||
#include "rclcpp/node_interfaces/node_waitables.hpp"
|
#include "rclcpp/node_interfaces/node_waitables.hpp"
|
||||||
|
|
||||||
using rclcpp::Node;
|
using rclcpp::Node;
|
||||||
|
using rclcpp::NodeOptions;
|
||||||
using rclcpp::exceptions::throw_from_rcl_error;
|
using rclcpp::exceptions::throw_from_rcl_error;
|
||||||
|
|
||||||
Node::Node(
|
Node::Node(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
const std::string & namespace_,
|
const NodeOptions & options)
|
||||||
bool use_intra_process_comms)
|
: Node(node_name, "", options)
|
||||||
: Node(
|
{
|
||||||
node_name,
|
}
|
||||||
namespace_,
|
|
||||||
rclcpp::contexts::default_context::get_global_default_context(),
|
|
||||||
{},
|
|
||||||
{},
|
|
||||||
true,
|
|
||||||
use_intra_process_comms,
|
|
||||||
true)
|
|
||||||
{}
|
|
||||||
|
|
||||||
Node::Node(
|
Node::Node(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
const std::string & namespace_,
|
const std::string & namespace_,
|
||||||
rclcpp::Context::SharedPtr context,
|
const NodeOptions & options)
|
||||||
const std::vector<std::string> & arguments,
|
|
||||||
const std::vector<rclcpp::Parameter> & initial_parameters,
|
|
||||||
bool use_global_arguments,
|
|
||||||
bool use_intra_process_comms,
|
|
||||||
bool start_parameter_services)
|
|
||||||
: node_base_(new rclcpp::node_interfaces::NodeBase(
|
: node_base_(new rclcpp::node_interfaces::NodeBase(
|
||||||
node_name, namespace_, context, arguments, use_global_arguments)),
|
node_name, namespace_, options)),
|
||||||
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
|
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
|
||||||
node_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
|
node_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
|
||||||
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
||||||
|
@ -80,9 +68,9 @@ Node::Node(
|
||||||
node_topics_,
|
node_topics_,
|
||||||
node_services_,
|
node_services_,
|
||||||
node_clock_,
|
node_clock_,
|
||||||
initial_parameters,
|
options.initial_parameters(),
|
||||||
use_intra_process_comms,
|
options.use_intra_process_comms(),
|
||||||
start_parameter_services
|
options.start_parameter_services()
|
||||||
)),
|
)),
|
||||||
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
|
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
|
||||||
node_base_,
|
node_base_,
|
||||||
|
@ -94,7 +82,7 @@ Node::Node(
|
||||||
node_parameters_
|
node_parameters_
|
||||||
)),
|
)),
|
||||||
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
||||||
use_intra_process_comms_(use_intra_process_comms)
|
use_intra_process_comms_(options.use_intra_process_comms())
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -32,10 +32,8 @@ using rclcpp::node_interfaces::NodeBase;
|
||||||
NodeBase::NodeBase(
|
NodeBase::NodeBase(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
const std::string & namespace_,
|
const std::string & namespace_,
|
||||||
rclcpp::Context::SharedPtr context,
|
const rclcpp::NodeOptions & options)
|
||||||
const std::vector<std::string> & arguments,
|
: context_(options.context()),
|
||||||
bool use_global_arguments)
|
|
||||||
: context_(context),
|
|
||||||
node_handle_(nullptr),
|
node_handle_(nullptr),
|
||||||
default_callback_group_(nullptr),
|
default_callback_group_(nullptr),
|
||||||
associated_with_executor_(false),
|
associated_with_executor_(false),
|
||||||
|
@ -44,7 +42,7 @@ NodeBase::NodeBase(
|
||||||
// Setup the guard condition that is notified when changes occur in the graph.
|
// Setup the guard condition that is notified when changes occur in the graph.
|
||||||
rcl_guard_condition_options_t guard_condition_options = rcl_guard_condition_get_default_options();
|
rcl_guard_condition_options_t guard_condition_options = rcl_guard_condition_get_default_options();
|
||||||
rcl_ret_t ret = rcl_guard_condition_init(
|
rcl_ret_t ret = rcl_guard_condition_init(
|
||||||
¬ify_guard_condition_, context->get_rcl_context().get(), guard_condition_options);
|
¬ify_guard_condition_, options.context()->get_rcl_context().get(), guard_condition_options);
|
||||||
if (ret != RCL_RET_OK) {
|
if (ret != RCL_RET_OK) {
|
||||||
throw_from_rcl_error(ret, "failed to create interrupt guard condition");
|
throw_from_rcl_error(ret, "failed to create interrupt guard condition");
|
||||||
}
|
}
|
||||||
|
@ -59,76 +57,16 @@ NodeBase::NodeBase(
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
// Determine the domain id based on the options and the ROS_DOMAIN_ID env variable.
|
|
||||||
size_t domain_id = 0;
|
|
||||||
char * ros_domain_id = nullptr;
|
|
||||||
const char * env_var = "ROS_DOMAIN_ID";
|
|
||||||
#ifndef _WIN32
|
|
||||||
ros_domain_id = getenv(env_var);
|
|
||||||
#else
|
|
||||||
size_t ros_domain_id_size;
|
|
||||||
_dupenv_s(&ros_domain_id, &ros_domain_id_size, env_var);
|
|
||||||
#endif
|
|
||||||
if (ros_domain_id) {
|
|
||||||
uint32_t number = strtoul(ros_domain_id, NULL, 0);
|
|
||||||
if (number == (std::numeric_limits<uint32_t>::max)()) {
|
|
||||||
// Finalize the interrupt guard condition.
|
|
||||||
finalize_notify_guard_condition();
|
|
||||||
#ifdef _WIN32
|
|
||||||
// free the ros_domain_id before throwing, if getenv was used on Windows
|
|
||||||
free(ros_domain_id);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
throw std::runtime_error("failed to interpret ROS_DOMAIN_ID as integral number");
|
|
||||||
}
|
|
||||||
domain_id = static_cast<size_t>(number);
|
|
||||||
#ifdef _WIN32
|
|
||||||
free(ros_domain_id);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
// Create the rcl node and store it in a shared_ptr with a custom destructor.
|
// Create the rcl node and store it in a shared_ptr with a custom destructor.
|
||||||
std::unique_ptr<rcl_node_t> rcl_node(new rcl_node_t(rcl_get_zero_initialized_node()));
|
std::unique_ptr<rcl_node_t> rcl_node(new rcl_node_t(rcl_get_zero_initialized_node()));
|
||||||
|
|
||||||
rcl_node_options_t options = rcl_node_get_default_options();
|
|
||||||
std::unique_ptr<const char *[]> c_args;
|
|
||||||
if (!arguments.empty()) {
|
|
||||||
c_args.reset(new const char *[arguments.size()]);
|
|
||||||
for (std::size_t i = 0; i < arguments.size(); ++i) {
|
|
||||||
c_args[i] = arguments[i].c_str();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
// TODO(sloretz) Pass an allocator to argument parsing
|
|
||||||
if (arguments.size() > std::numeric_limits<int>::max()) {
|
|
||||||
throw_from_rcl_error(RCL_RET_INVALID_ARGUMENT, "Too many args");
|
|
||||||
}
|
|
||||||
ret = rcl_parse_arguments(
|
|
||||||
static_cast<int>(arguments.size()), c_args.get(), rcl_get_default_allocator(),
|
|
||||||
&(options.arguments));
|
|
||||||
if (RCL_RET_OK != ret) {
|
|
||||||
finalize_notify_guard_condition();
|
|
||||||
throw_from_rcl_error(ret, "failed to parse arguments");
|
|
||||||
}
|
|
||||||
|
|
||||||
options.use_global_arguments = use_global_arguments;
|
|
||||||
// TODO(wjwwood): pass the Allocator to the options
|
|
||||||
options.domain_id = domain_id;
|
|
||||||
|
|
||||||
ret = rcl_node_init(
|
ret = rcl_node_init(
|
||||||
rcl_node.get(),
|
rcl_node.get(),
|
||||||
node_name.c_str(), namespace_.c_str(),
|
node_name.c_str(), namespace_.c_str(),
|
||||||
context->get_rcl_context().get(), &options);
|
options.context()->get_rcl_context().get(), options.get_rcl_node_options());
|
||||||
if (ret != RCL_RET_OK) {
|
if (ret != RCL_RET_OK) {
|
||||||
// Finalize the interrupt guard condition.
|
// Finalize the interrupt guard condition.
|
||||||
finalize_notify_guard_condition();
|
finalize_notify_guard_condition();
|
||||||
// Finalize previously allocated node arguments
|
|
||||||
if (RCL_RET_OK != rcl_arguments_fini(&options.arguments)) {
|
|
||||||
// Print message because exception will be thrown later in this code block
|
|
||||||
RCUTILS_LOG_ERROR_NAMED(
|
|
||||||
"rclcpp",
|
|
||||||
"Failed to fini arguments during error handling: %s", rcl_get_error_string().str);
|
|
||||||
rcl_reset_error();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (ret == RCL_RET_NODE_INVALID_NAME) {
|
if (ret == RCL_RET_NODE_INVALID_NAME) {
|
||||||
rcl_reset_error(); // discard rcl_node_init error
|
rcl_reset_error(); // discard rcl_node_init error
|
||||||
|
@ -195,15 +133,6 @@ NodeBase::NodeBase(
|
||||||
|
|
||||||
// Indicate the notify_guard_condition is now valid.
|
// Indicate the notify_guard_condition is now valid.
|
||||||
notify_guard_condition_is_valid_ = true;
|
notify_guard_condition_is_valid_ = true;
|
||||||
|
|
||||||
// Finalize previously allocated node arguments
|
|
||||||
if (RCL_RET_OK != rcl_arguments_fini(&options.arguments)) {
|
|
||||||
// print message because throwing would prevent the destructor from being called
|
|
||||||
RCUTILS_LOG_ERROR_NAMED(
|
|
||||||
"rclcpp",
|
|
||||||
"Failed to fini arguments: %s", rcl_get_error_string().str);
|
|
||||||
rcl_reset_error();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
NodeBase::~NodeBase()
|
NodeBase::~NodeBase()
|
||||||
|
|
241
rclcpp/src/rclcpp/node_options.cpp
Normal file
241
rclcpp/src/rclcpp/node_options.cpp
Normal file
|
@ -0,0 +1,241 @@
|
||||||
|
// 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.
|
||||||
|
|
||||||
|
#include "rclcpp/node_options.hpp"
|
||||||
|
|
||||||
|
#include <limits>
|
||||||
|
#include <memory>
|
||||||
|
#include <string>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
#include "rclcpp/exceptions.hpp"
|
||||||
|
#include "rclcpp/logging.hpp"
|
||||||
|
|
||||||
|
using rclcpp::exceptions::throw_from_rcl_error;
|
||||||
|
|
||||||
|
namespace rclcpp
|
||||||
|
{
|
||||||
|
|
||||||
|
namespace detail
|
||||||
|
{
|
||||||
|
static
|
||||||
|
void
|
||||||
|
rcl_node_options_t_destructor(rcl_node_options_t * node_options)
|
||||||
|
{
|
||||||
|
if (node_options) {
|
||||||
|
rcl_ret_t ret = rcl_node_options_fini(node_options);
|
||||||
|
if (RCL_RET_OK != ret) {
|
||||||
|
// Cannot throw here, as it may be called in the destructor.
|
||||||
|
RCLCPP_ERROR(
|
||||||
|
rclcpp::get_logger("rclcpp"),
|
||||||
|
"failed to finalize rcl node options: %s", rcl_get_error_string().str);
|
||||||
|
rcl_reset_error();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} // namespace detail
|
||||||
|
|
||||||
|
NodeOptions::NodeOptions(rcl_allocator_t allocator)
|
||||||
|
: node_options_(nullptr, detail::rcl_node_options_t_destructor), allocator_(allocator)
|
||||||
|
{}
|
||||||
|
|
||||||
|
NodeOptions::NodeOptions(const NodeOptions & other)
|
||||||
|
: node_options_(nullptr, detail::rcl_node_options_t_destructor)
|
||||||
|
{
|
||||||
|
*this = other;
|
||||||
|
}
|
||||||
|
|
||||||
|
NodeOptions &
|
||||||
|
NodeOptions::operator=(const NodeOptions & other)
|
||||||
|
{
|
||||||
|
if (this != &other) {
|
||||||
|
this->context_ = other.context_;
|
||||||
|
this->arguments_ = other.arguments_;
|
||||||
|
this->initial_parameters_ = other.initial_parameters_;
|
||||||
|
this->use_global_arguments_ = other.use_global_arguments_;
|
||||||
|
this->use_intra_process_comms_ = other.use_intra_process_comms_;
|
||||||
|
this->start_parameter_services_ = other.start_parameter_services_;
|
||||||
|
this->allocator_ = other.allocator_;
|
||||||
|
}
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
const rcl_node_options_t *
|
||||||
|
NodeOptions::get_rcl_node_options() const
|
||||||
|
{
|
||||||
|
// If it is nullptr, create it on demand.
|
||||||
|
if (!node_options_) {
|
||||||
|
node_options_.reset(new rcl_node_options_t);
|
||||||
|
*node_options_ = rcl_node_get_default_options();
|
||||||
|
node_options_->allocator = this->allocator_;
|
||||||
|
node_options_->use_global_arguments = this->use_global_arguments_;
|
||||||
|
node_options_->domain_id = this->get_domain_id_from_env();
|
||||||
|
|
||||||
|
std::unique_ptr<const char *[]> c_args;
|
||||||
|
if (!this->arguments_.empty()) {
|
||||||
|
c_args.reset(new const char *[this->arguments_.size()]);
|
||||||
|
for (std::size_t i = 0; i < this->arguments_.size(); ++i) {
|
||||||
|
c_args[i] = this->arguments_[i].c_str();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (this->arguments_.size() > std::numeric_limits<int>::max()) {
|
||||||
|
throw_from_rcl_error(RCL_RET_INVALID_ARGUMENT, "Too many args");
|
||||||
|
}
|
||||||
|
|
||||||
|
rmw_ret_t ret = rcl_parse_arguments(
|
||||||
|
static_cast<int>(this->arguments_.size()), c_args.get(), this->allocator_,
|
||||||
|
&(node_options_->arguments));
|
||||||
|
|
||||||
|
if (RCL_RET_OK != ret) {
|
||||||
|
throw_from_rcl_error(ret, "failed to parse arguments");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return node_options_.get();
|
||||||
|
}
|
||||||
|
|
||||||
|
rclcpp::Context::SharedPtr
|
||||||
|
NodeOptions::context() const
|
||||||
|
{
|
||||||
|
return this->context_;
|
||||||
|
}
|
||||||
|
|
||||||
|
NodeOptions &
|
||||||
|
NodeOptions::context(rclcpp::Context::SharedPtr context)
|
||||||
|
{
|
||||||
|
this->context_ = context;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
const std::vector<std::string> &
|
||||||
|
NodeOptions::arguments() const
|
||||||
|
{
|
||||||
|
return this->arguments_;
|
||||||
|
}
|
||||||
|
|
||||||
|
NodeOptions &
|
||||||
|
NodeOptions::arguments(const std::vector<std::string> & arguments)
|
||||||
|
{
|
||||||
|
this->node_options_.reset(); // reset node options to make it be recreated on next access.
|
||||||
|
this->arguments_ = arguments;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<rclcpp::Parameter> &
|
||||||
|
NodeOptions::initial_parameters()
|
||||||
|
{
|
||||||
|
return this->initial_parameters_;
|
||||||
|
}
|
||||||
|
|
||||||
|
const std::vector<rclcpp::Parameter> &
|
||||||
|
NodeOptions::initial_parameters() const
|
||||||
|
{
|
||||||
|
return this->initial_parameters_;
|
||||||
|
}
|
||||||
|
|
||||||
|
NodeOptions &
|
||||||
|
NodeOptions::initial_parameters(const std::vector<rclcpp::Parameter> & initial_parameters)
|
||||||
|
{
|
||||||
|
this->initial_parameters_ = initial_parameters;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
const bool &
|
||||||
|
NodeOptions::use_global_arguments() const
|
||||||
|
{
|
||||||
|
return this->node_options_->use_global_arguments;
|
||||||
|
}
|
||||||
|
|
||||||
|
NodeOptions &
|
||||||
|
NodeOptions::use_global_arguments(const bool & use_global_arguments)
|
||||||
|
{
|
||||||
|
this->node_options_.reset(); // reset node options to make it be recreated on next access.
|
||||||
|
this->use_global_arguments_ = use_global_arguments;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
const bool &
|
||||||
|
NodeOptions::use_intra_process_comms() const
|
||||||
|
{
|
||||||
|
return this->use_intra_process_comms_;
|
||||||
|
}
|
||||||
|
|
||||||
|
NodeOptions &
|
||||||
|
NodeOptions::use_intra_process_comms(const bool & use_intra_process_comms)
|
||||||
|
{
|
||||||
|
this->use_intra_process_comms_ = use_intra_process_comms;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
const bool &
|
||||||
|
NodeOptions::start_parameter_services() const
|
||||||
|
{
|
||||||
|
return this->start_parameter_services_;
|
||||||
|
}
|
||||||
|
|
||||||
|
NodeOptions &
|
||||||
|
NodeOptions::start_parameter_services(const bool & start_parameter_services)
|
||||||
|
{
|
||||||
|
this->start_parameter_services_ = start_parameter_services;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
const rcl_allocator_t &
|
||||||
|
NodeOptions::allocator() const
|
||||||
|
{
|
||||||
|
return this->allocator_;
|
||||||
|
}
|
||||||
|
|
||||||
|
NodeOptions &
|
||||||
|
NodeOptions::allocator(rcl_allocator_t allocator)
|
||||||
|
{
|
||||||
|
this->node_options_.reset(); // reset node options to make it be recreated on next access.
|
||||||
|
this->allocator_ = allocator;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO(wjwwood): reuse rcutils_get_env() to avoid code duplication.
|
||||||
|
// See also: https://github.com/ros2/rcl/issues/119
|
||||||
|
size_t
|
||||||
|
NodeOptions::get_domain_id_from_env() const
|
||||||
|
{
|
||||||
|
// Determine the domain id based on the options and the ROS_DOMAIN_ID env variable.
|
||||||
|
size_t domain_id = std::numeric_limits<size_t>::max();
|
||||||
|
char * ros_domain_id = nullptr;
|
||||||
|
const char * env_var = "ROS_DOMAIN_ID";
|
||||||
|
#ifndef _WIN32
|
||||||
|
ros_domain_id = getenv(env_var);
|
||||||
|
#else
|
||||||
|
size_t ros_domain_id_size;
|
||||||
|
_dupenv_s(&ros_domain_id, &ros_domain_id_size, env_var);
|
||||||
|
#endif
|
||||||
|
if (ros_domain_id) {
|
||||||
|
uint32_t number = strtoul(ros_domain_id, NULL, 0);
|
||||||
|
if (number == (std::numeric_limits<uint32_t>::max)()) {
|
||||||
|
#ifdef _WIN32
|
||||||
|
// free the ros_domain_id before throwing, if getenv was used on Windows
|
||||||
|
free(ros_domain_id);
|
||||||
|
#endif
|
||||||
|
throw std::runtime_error("failed to interpret ROS_DOMAIN_ID as integral number");
|
||||||
|
}
|
||||||
|
domain_id = static_cast<size_t>(number);
|
||||||
|
#ifdef _WIN32
|
||||||
|
free(ros_domain_id);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
return domain_id;
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace rclcpp
|
|
@ -20,6 +20,7 @@
|
||||||
|
|
||||||
#include "rclcpp/exceptions.hpp"
|
#include "rclcpp/exceptions.hpp"
|
||||||
#include "rclcpp/node.hpp"
|
#include "rclcpp/node.hpp"
|
||||||
|
#include "rclcpp/node_options.hpp"
|
||||||
#include "rclcpp/rclcpp.hpp"
|
#include "rclcpp/rclcpp.hpp"
|
||||||
|
|
||||||
class TestNodeWithGlobalArgs : public ::testing::Test
|
class TestNodeWithGlobalArgs : public ::testing::Test
|
||||||
|
@ -33,32 +34,26 @@ protected:
|
||||||
};
|
};
|
||||||
|
|
||||||
TEST_F(TestNodeWithGlobalArgs, local_arguments_before_global) {
|
TEST_F(TestNodeWithGlobalArgs, local_arguments_before_global) {
|
||||||
auto context = rclcpp::contexts::default_context::get_global_default_context();
|
auto options = rclcpp::NodeOptions()
|
||||||
const std::vector<std::string> arguments = {"__node:=local_arguments_test"};
|
.arguments({"__node:=local_arguments_test"});
|
||||||
const std::vector<rclcpp::Parameter> initial_values = {};
|
|
||||||
const bool use_global_arguments = true;
|
auto node = rclcpp::Node::make_shared("orig_name", options);
|
||||||
const bool use_intra_process = false;
|
|
||||||
auto node = rclcpp::Node::make_shared(
|
|
||||||
"orig_name", "", context, arguments, initial_values, use_global_arguments, use_intra_process);
|
|
||||||
EXPECT_STREQ("local_arguments_test", node->get_name());
|
EXPECT_STREQ("local_arguments_test", node->get_name());
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(TestNodeWithGlobalArgs, use_or_ignore_global_arguments) {
|
TEST_F(TestNodeWithGlobalArgs, use_or_ignore_global_arguments) {
|
||||||
auto context = rclcpp::contexts::default_context::get_global_default_context();
|
|
||||||
const std::vector<std::string> arguments = {};
|
|
||||||
const std::vector<rclcpp::Parameter> initial_values = {};
|
|
||||||
const bool use_intra_process = false;
|
|
||||||
|
|
||||||
{ // Don't use global args
|
{ // Don't use global args
|
||||||
const bool use_global_arguments = false;
|
auto options = rclcpp::NodeOptions()
|
||||||
auto node = rclcpp::Node::make_shared(
|
.use_global_arguments(false);
|
||||||
"orig_name", "", context, arguments, initial_values, use_global_arguments, use_intra_process);
|
|
||||||
|
auto node = rclcpp::Node::make_shared("orig_name", options);
|
||||||
EXPECT_STREQ("orig_name", node->get_name());
|
EXPECT_STREQ("orig_name", node->get_name());
|
||||||
}
|
}
|
||||||
{ // Do use global args
|
{ // Do use global args
|
||||||
const bool use_global_arguments = true;
|
auto options = rclcpp::NodeOptions()
|
||||||
auto node = rclcpp::Node::make_shared(
|
.use_global_arguments(true);
|
||||||
"orig_name", "", context, arguments, initial_values, use_global_arguments, use_intra_process);
|
|
||||||
|
auto node = rclcpp::Node::make_shared("orig_name", options);
|
||||||
EXPECT_STREQ("global_node_name", node->get_name());
|
EXPECT_STREQ("global_node_name", node->get_name());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -36,29 +36,28 @@ protected:
|
||||||
};
|
};
|
||||||
|
|
||||||
TEST_F(TestNodeWithInitialValues, no_initial_values) {
|
TEST_F(TestNodeWithInitialValues, no_initial_values) {
|
||||||
auto context = rclcpp::contexts::default_context::get_global_default_context();
|
auto options = rclcpp::NodeOptions()
|
||||||
const std::vector<std::string> arguments = {};
|
.use_intra_process_comms(false)
|
||||||
const std::vector<rclcpp::Parameter> initial_values = {};
|
.use_global_arguments(false);
|
||||||
const bool use_global_arguments = false;
|
|
||||||
const bool use_intra_process = false;
|
auto node = rclcpp::Node::make_shared("node_name", options);
|
||||||
auto node = rclcpp::Node::make_shared(
|
|
||||||
"node_name", "", context, arguments, initial_values, use_global_arguments, use_intra_process);
|
|
||||||
auto list_params_result = node->list_parameters({}, 0);
|
auto list_params_result = node->list_parameters({}, 0);
|
||||||
EXPECT_EQ(0u, list_params_result.names.size());
|
EXPECT_EQ(0u, list_params_result.names.size());
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(TestNodeWithInitialValues, multiple_initial_values) {
|
TEST_F(TestNodeWithInitialValues, multiple_initial_values) {
|
||||||
auto context = rclcpp::contexts::default_context::get_global_default_context();
|
auto parameters = std::vector<rclcpp::Parameter>({
|
||||||
const std::vector<std::string> arguments = {};
|
|
||||||
const std::vector<rclcpp::Parameter> initial_values = {
|
|
||||||
rclcpp::Parameter("foo", true),
|
rclcpp::Parameter("foo", true),
|
||||||
rclcpp::Parameter("bar", "hello world"),
|
rclcpp::Parameter("bar", "hello world"),
|
||||||
rclcpp::Parameter("baz", std::vector<double>{3.14, 2.718})
|
rclcpp::Parameter("baz", std::vector<double>{3.14, 2.718})
|
||||||
};
|
});
|
||||||
const bool use_global_arguments = false;
|
|
||||||
const bool use_intra_process = false;
|
auto options = rclcpp::NodeOptions()
|
||||||
auto node = rclcpp::Node::make_shared(
|
.initial_parameters(parameters)
|
||||||
"node_name", "", context, arguments, initial_values, use_global_arguments, use_intra_process);
|
.use_global_arguments(false)
|
||||||
|
.use_intra_process_comms(false);
|
||||||
|
|
||||||
|
auto node = rclcpp::Node::make_shared("node_name", options);
|
||||||
auto list_params_result = node->list_parameters({}, 0);
|
auto list_params_result = node->list_parameters({}, 0);
|
||||||
EXPECT_EQ(3u, list_params_result.names.size());
|
EXPECT_EQ(3u, list_params_result.names.size());
|
||||||
EXPECT_TRUE(node->get_parameter("foo").get_value<bool>());
|
EXPECT_TRUE(node->get_parameter("foo").get_value<bool>());
|
||||||
|
|
|
@ -36,6 +36,7 @@
|
||||||
#include "rclcpp/logger.hpp"
|
#include "rclcpp/logger.hpp"
|
||||||
#include "rclcpp/macros.hpp"
|
#include "rclcpp/macros.hpp"
|
||||||
#include "rclcpp/message_memory_strategy.hpp"
|
#include "rclcpp/message_memory_strategy.hpp"
|
||||||
|
#include "rclcpp/node_options.hpp"
|
||||||
#include "rclcpp/node_interfaces/node_base_interface.hpp"
|
#include "rclcpp/node_interfaces/node_base_interface.hpp"
|
||||||
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
|
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
|
||||||
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
|
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
|
||||||
|
@ -75,39 +76,25 @@ public:
|
||||||
/**
|
/**
|
||||||
* \param[in] node_name Name of the node.
|
* \param[in] node_name Name of the node.
|
||||||
* \param[in] namespace_ Namespace of the node.
|
* \param[in] namespace_ Namespace of the node.
|
||||||
* \param[in] use_intra_process_comms True to use the optimized intra-process communication
|
* \param[in] options Additional options to control creation of the node.
|
||||||
* pipeline to pass messages between nodes in the same process using shared memory.
|
|
||||||
*/
|
*/
|
||||||
RCLCPP_LIFECYCLE_PUBLIC
|
RCLCPP_LIFECYCLE_PUBLIC
|
||||||
explicit LifecycleNode(
|
explicit LifecycleNode(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
const std::string & namespace_ = "",
|
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
|
||||||
bool use_intra_process_comms = false);
|
|
||||||
|
|
||||||
/// Create a node based on the node name and a rclcpp::Context.
|
/// Create a node based on the node name and a rclcpp::Context.
|
||||||
/**
|
/**
|
||||||
* \param[in] node_name Name of the node.
|
* \param[in] node_name Name of the node.
|
||||||
* \param[in] namespace_ Namespace of the node.
|
* \param[in] namespace_ Namespace of the node.
|
||||||
* \param[in] context The context for the node (usually represents the state of a process).
|
* \param[in] context The context for the node (usually represents the state of a process).
|
||||||
* \param[in] arguments Command line arguments that should apply only to this node.
|
* \param[in] options Additional options to control creation of the node.
|
||||||
* \param[in] initial_parameters a list of initial values for parameters on the node.
|
|
||||||
* This can be used to provide remapping rules that only affect one instance.
|
|
||||||
* \param[in] use_global_arguments False to prevent node using arguments passed to the process.
|
|
||||||
* \param[in] use_intra_process_comms True to use the optimized intra-process communication
|
|
||||||
* pipeline to pass messages between nodes in the same process using shared memory.
|
|
||||||
* \param[in] start_parameter_services True to setup ROS interfaces for accessing parameters
|
|
||||||
* in the node.
|
|
||||||
*/
|
*/
|
||||||
RCLCPP_LIFECYCLE_PUBLIC
|
RCLCPP_LIFECYCLE_PUBLIC
|
||||||
LifecycleNode(
|
LifecycleNode(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
const std::string & namespace_,
|
const std::string & namespace_,
|
||||||
rclcpp::Context::SharedPtr context,
|
const rclcpp::NodeOptions & options);
|
||||||
const std::vector<std::string> & arguments,
|
|
||||||
const std::vector<rclcpp::Parameter> & initial_parameters,
|
|
||||||
bool use_global_arguments = true,
|
|
||||||
bool use_intra_process_comms = false,
|
|
||||||
bool start_parameter_services = true);
|
|
||||||
|
|
||||||
RCLCPP_LIFECYCLE_PUBLIC
|
RCLCPP_LIFECYCLE_PUBLIC
|
||||||
virtual ~LifecycleNode();
|
virtual ~LifecycleNode();
|
||||||
|
|
|
@ -45,30 +45,19 @@ namespace rclcpp_lifecycle
|
||||||
|
|
||||||
LifecycleNode::LifecycleNode(
|
LifecycleNode::LifecycleNode(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
const std::string & namespace_,
|
const rclcpp::NodeOptions & options)
|
||||||
bool use_intra_process_comms)
|
|
||||||
: LifecycleNode(
|
: LifecycleNode(
|
||||||
node_name,
|
node_name,
|
||||||
namespace_,
|
"",
|
||||||
rclcpp::contexts::default_context::get_global_default_context(),
|
options)
|
||||||
{},
|
|
||||||
{},
|
|
||||||
true,
|
|
||||||
use_intra_process_comms,
|
|
||||||
true)
|
|
||||||
{}
|
{}
|
||||||
|
|
||||||
LifecycleNode::LifecycleNode(
|
LifecycleNode::LifecycleNode(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
const std::string & namespace_,
|
const std::string & namespace_,
|
||||||
rclcpp::Context::SharedPtr context,
|
const rclcpp::NodeOptions & options)
|
||||||
const std::vector<std::string> & arguments,
|
|
||||||
const std::vector<rclcpp::Parameter> & initial_parameters,
|
|
||||||
bool use_global_arguments,
|
|
||||||
bool use_intra_process_comms,
|
|
||||||
bool start_parameter_services)
|
|
||||||
: node_base_(new rclcpp::node_interfaces::NodeBase(
|
: node_base_(new rclcpp::node_interfaces::NodeBase(
|
||||||
node_name, namespace_, context, arguments, use_global_arguments)),
|
node_name, namespace_, options)),
|
||||||
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
|
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
|
||||||
node_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
|
node_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
|
||||||
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
||||||
|
@ -86,12 +75,12 @@ LifecycleNode::LifecycleNode(
|
||||||
node_topics_,
|
node_topics_,
|
||||||
node_services_,
|
node_services_,
|
||||||
node_clock_,
|
node_clock_,
|
||||||
initial_parameters,
|
options.initial_parameters(),
|
||||||
use_intra_process_comms,
|
options.use_intra_process_comms(),
|
||||||
start_parameter_services
|
options.start_parameter_services()
|
||||||
)),
|
)),
|
||||||
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
||||||
use_intra_process_comms_(use_intra_process_comms),
|
use_intra_process_comms_(options.use_intra_process_comms()),
|
||||||
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
|
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
|
||||||
{
|
{
|
||||||
impl_->init();
|
impl_->init();
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue