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:
Michael Carroll 2019-02-06 01:10:43 -06:00 committed by William Woodall
parent c7ac39a0e6
commit 0f9098e9b6
11 changed files with 506 additions and 194 deletions

View file

@ -36,6 +36,7 @@
#include "rclcpp/logger.hpp"
#include "rclcpp/macros.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_clock_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] namespace_ Namespace 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.
* \param[in] options Additional options to control creation of the node.
*/
RCLCPP_LIFECYCLE_PUBLIC
explicit LifecycleNode(
const std::string & node_name,
const std::string & namespace_ = "",
bool use_intra_process_comms = false);
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
/// Create a node based on the node name and a rclcpp::Context.
/**
* \param[in] node_name Name 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] 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.
* \param[in] options Additional options to control creation of the node.
*/
RCLCPP_LIFECYCLE_PUBLIC
LifecycleNode(
const std::string & node_name,
const std::string & namespace_,
rclcpp::Context::SharedPtr context,
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);
const rclcpp::NodeOptions & options);
RCLCPP_LIFECYCLE_PUBLIC
virtual ~LifecycleNode();

View file

@ -45,30 +45,19 @@ namespace rclcpp_lifecycle
LifecycleNode::LifecycleNode(
const std::string & node_name,
const std::string & namespace_,
bool use_intra_process_comms)
const rclcpp::NodeOptions & options)
: LifecycleNode(
node_name,
namespace_,
rclcpp::contexts::default_context::get_global_default_context(),
{},
{},
true,
use_intra_process_comms,
true)
"",
options)
{}
LifecycleNode::LifecycleNode(
const std::string & node_name,
const std::string & namespace_,
rclcpp::Context::SharedPtr context,
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)
const rclcpp::NodeOptions & options)
: 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_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
@ -86,12 +75,12 @@ LifecycleNode::LifecycleNode(
node_topics_,
node_services_,
node_clock_,
initial_parameters,
use_intra_process_comms,
start_parameter_services
options.initial_parameters(),
options.use_intra_process_comms(),
options.start_parameter_services()
)),
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_->init();