Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add CLI args to Node constructor #461

Merged
merged 2 commits into from
Apr 17, 2018
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
10 changes: 10 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -191,6 +191,16 @@ if(BUILD_TESTING)
)
target_link_libraries(test_node ${PROJECT_NAME})
endif()
ament_add_gtest(test_node_global_args test/test_node_global_args.cpp)
if(TARGET test_node_global_args)
target_include_directories(test_node_global_args PUBLIC
${rcl_interfaces_INCLUDE_DIRS}
${rmw_INCLUDE_DIRS}
${rosidl_generator_cpp_INCLUDE_DIRS}
${rosidl_typesupport_cpp_INCLUDE_DIRS}
)
target_link_libraries(test_node_global_args ${PROJECT_NAME})
endif()
ament_add_gtest(test_parameter_events_filter test/test_parameter_events_filter.cpp)
if(TARGET test_parameter_events_filter)
target_include_directories(test_parameter_events_filter PUBLIC
Expand Down
5 changes: 5 additions & 0 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,9 @@ class Node : public std::enable_shared_from_this<Node>
* \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.
* 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.
*/
Expand All @@ -92,6 +95,8 @@ class Node : public std::enable_shared_from_this<Node>
const std::string & node_name,
const std::string & namespace_,
rclcpp::Context::SharedPtr context,
const std::vector<std::string> & arguments,
bool use_global_arguments = true,
bool use_intra_process_comms = false);

RCLCPP_PUBLIC
Expand Down
4 changes: 3 additions & 1 deletion rclcpp/include/rclcpp/node_interfaces/node_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,9 @@ class NodeBase : public NodeBaseInterface
NodeBase(
const std::string & node_name,
const std::string & namespace_,
rclcpp::Context::SharedPtr context);
rclcpp::Context::SharedPtr context,
const std::vector<std::string> & arguments,
bool use_global_arguments);

RCLCPP_PUBLIC
virtual
Expand Down
7 changes: 6 additions & 1 deletion rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,15 +43,20 @@ Node::Node(
node_name,
namespace_,
rclcpp::contexts::default_context::get_global_default_context(),
{},
true,
use_intra_process_comms)
{}

Node::Node(
const std::string & node_name,
const std::string & namespace_,
rclcpp::Context::SharedPtr context,
const std::vector<std::string> & arguments,
bool use_global_arguments,
bool use_intra_process_comms)
: node_base_(new rclcpp::node_interfaces::NodeBase(node_name, namespace_, context)),
: node_base_(new rclcpp::node_interfaces::NodeBase(
node_name, namespace_, context, arguments, use_global_arguments)),
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())),
Expand Down
30 changes: 24 additions & 6 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include "rclcpp/node_interfaces/node_base.hpp"

#include "rcl/arguments.h"
#include "rclcpp/exceptions.hpp"
#include "rcutils/logging_macros.h"
#include "rmw/validate_node_name.h"
Expand All @@ -31,7 +32,9 @@ using rclcpp::node_interfaces::NodeBase;
NodeBase::NodeBase(
const std::string & node_name,
const std::string & namespace_,
rclcpp::Context::SharedPtr context)
rclcpp::Context::SharedPtr context,
const std::vector<std::string> & arguments,
bool use_global_arguments)
: context_(context),
node_handle_(nullptr),
default_callback_group_(nullptr),
Expand Down Expand Up @@ -84,18 +87,33 @@ NodeBase::NodeBase(
}

// Create the rcl node and store it in a shared_ptr with a custom destructor.
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()));
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I changed this only to get rid of false positive "double free" error from cppcheck. It didn't like that it saw two delete rcl_node; statements: one in the error handling after calling rcl_parse_arguments(), and another in the error handling of rcl_node_init().


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
ret = rcl_parse_arguments(
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(rcl_node, node_name.c_str(), namespace_.c_str(), &options);

ret = rcl_node_init(rcl_node.get(), node_name.c_str(), namespace_.c_str(), &options);
if (ret != RCL_RET_OK) {
// Finalize the interrupt guard condition.
finalize_notify_guard_condition();

delete rcl_node;

if (ret == RCL_RET_NODE_INVALID_NAME) {
rcl_reset_error(); // discard rcl_node_init error
int validation_result;
Expand Down Expand Up @@ -145,7 +163,7 @@ NodeBase::NodeBase(
}

node_handle_.reset(
rcl_node,
rcl_node.release(),
[](rcl_node_t * node) -> void {
if (rcl_node_fini(node) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
Expand Down
1 change: 1 addition & 0 deletions rclcpp/test/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include <string>
#include <memory>
#include <vector>

#include "rclcpp/exceptions.hpp"
#include "rclcpp/node.hpp"
Expand Down
62 changes: 62 additions & 0 deletions rclcpp/test/test_node_global_args.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
// Copyright 2018 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 <gtest/gtest.h>

#include <string>
#include <memory>
#include <vector>

#include "rclcpp/exceptions.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/rclcpp.hpp"

class TestNodeWithGlobalArgs : public ::testing::Test
{
protected:
static void SetUpTestCase()
{
const char * const args[] = {"proc", "__node:=global_node_name"};
rclcpp::init(2, args);
}
};

TEST_F(TestNodeWithGlobalArgs, local_arguments_before_global) {
auto context = rclcpp::contexts::default_context::get_global_default_context();
const std::vector<std::string> arguments = {"__node:=local_arguments_test"};
const bool use_global_arguments = true;
const bool use_intra_process = false;
auto node = rclcpp::Node::make_shared(
"orig_name", "", context, arguments, use_global_arguments, use_intra_process);
EXPECT_STREQ("local_arguments_test", node->get_name());
}

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 bool use_intra_process = false;

{ // Don't use global args
const bool use_global_arguments = false;
auto node = rclcpp::Node::make_shared(
"orig_name", "", context, arguments, use_global_arguments, use_intra_process);
EXPECT_STREQ("orig_name", node->get_name());
}
{ // Do use global args
const bool use_global_arguments = true;
auto node = rclcpp::Node::make_shared(
"orig_name", "", context, arguments, use_global_arguments, use_intra_process);
EXPECT_STREQ("global_node_name", node->get_name());
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,9 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
* \param[in] node_name Name of the node.
* \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.
* 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.
*/
Expand All @@ -96,6 +99,8 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
const std::string & node_name,
const std::string & namespace_,
rclcpp::Context::SharedPtr context,
const std::vector<std::string> & arguments,
bool use_global_arguments = true,
bool use_intra_process_comms = false);

RCLCPP_LIFECYCLE_PUBLIC
Expand Down
7 changes: 6 additions & 1 deletion rclcpp_lifecycle/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,15 +49,20 @@ LifecycleNode::LifecycleNode(
node_name,
namespace_,
rclcpp::contexts::default_context::get_global_default_context(),
{},
true,
use_intra_process_comms)
{}

LifecycleNode::LifecycleNode(
const std::string & node_name,
const std::string & namespace_,
rclcpp::Context::SharedPtr context,
const std::vector<std::string> & arguments,
bool use_global_arguments,
bool use_intra_process_comms)
: node_base_(new rclcpp::node_interfaces::NodeBase(node_name, namespace_, context)),
: node_base_(new rclcpp::node_interfaces::NodeBase(
node_name, namespace_, context, arguments, use_global_arguments)),
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())),
Expand Down