Pass initial parameter values to node constructor (#486)

* Pass parameter values to node constructor
This commit is contained in:
Shane Loretz 2018-06-05 15:29:20 -07:00 committed by GitHub
parent 8f793fdb4a
commit 84c8d58612
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
9 changed files with 100 additions and 3 deletions

View file

@ -89,6 +89,7 @@ public:
* \param[in] node_name 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
@ -100,6 +101,7 @@ public:
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);

View file

@ -51,6 +51,7 @@ LifecycleNode::LifecycleNode(
namespace_,
rclcpp::contexts::default_context::get_global_default_context(),
{},
{},
true,
use_intra_process_comms,
true)
@ -61,6 +62,7 @@ LifecycleNode::LifecycleNode(
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)
@ -75,6 +77,7 @@ LifecycleNode::LifecycleNode(
node_base_,
node_topics_,
node_services_,
initial_parameters,
use_intra_process_comms,
start_parameter_services
)),