Skip to content

Commit

Permalink
Use NodeInterfaceHandle as class name instead
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <methylDragon@gmail.com>
  • Loading branch information
methylDragon committed Nov 8, 2022
1 parent 0116a23 commit 6734ecf
Show file tree
Hide file tree
Showing 6 changed files with 69 additions and 58 deletions.
14 changes: 7 additions & 7 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -1449,19 +1449,19 @@ class Node : public std::enable_shared_from_this<Node>
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
get_node_time_source_interface();

/// Return a NodeHandle bound with the Node's internal node interfaces.
/// Return a NodeInterfaceHandle bound with the Node's internal node interfaces.
/**
* This overload binds all interfaces, if you want to bind a subset of interfaces, specify them
* in the template parameters of the templated method.
*
* \return a NodeHandle bound with the Node's internal node interfaces.
* \return a NodeInterfaceHandle bound with the Node's internal node interfaces.
*/
RCLCPP_PUBLIC
inline
rclcpp::NodeHandle<AllInterfaces>::SharedPtr
get_node_handle() {return std::make_shared<NodeHandle<AllInterfaces>>(this);}
rclcpp::NodeInterfaceHandle<AllInterfaces>::SharedPtr
get_node_handle() {return std::make_shared<NodeInterfaceHandle<AllInterfaces>>(this);}

/// Return a NodeHandle bound with the Node's internal node interfaces.
/// Return a NodeInterfaceHandle bound with the Node's internal node interfaces.
/**
* Specify which interfaces you want to bind using the temlplate parameters. Any unbound
* interfaces will be nullptr.
Expand All @@ -1476,10 +1476,10 @@ class Node : public std::enable_shared_from_this<Node>
* - ```node->get_node_handle<AllInterfaces>()``` will bind all interfaces.
* - ```node->get_node_handle()``` will bind all interfaces.
*
* \return a NodeHandle bound with the Node's internal node interfaces.
* \return a NodeInterfaceHandle bound with the Node's internal node interfaces.
*/
template<typename ... InterfaceTs>
typename rclcpp::NodeHandle<InterfaceTs...>::SharedPtr
typename rclcpp::NodeInterfaceHandle<InterfaceTs...>::SharedPtr
get_node_handle();

/// Return the sub-namespace, if this is a sub-node, otherwise an empty string.
Expand Down
29 changes: 16 additions & 13 deletions rclcpp/include/rclcpp/node_handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,14 +46,14 @@ struct AllInterfaces {};

/// A helper class for aggregating node interfaces
template<typename ... InterfaceTs>
class NodeHandle : public std::enable_shared_from_this<NodeHandle<InterfaceTs...>>
class NodeInterfaceHandle : public std::enable_shared_from_this<NodeInterfaceHandle<InterfaceTs...>>
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(NodeHandle)
RCLCPP_SMART_PTR_DEFINITIONS(NodeInterfaceHandle)

/// Create a new node handle with no bound node interfaces.
RCLCPP_PUBLIC
NodeHandle()
NodeInterfaceHandle()
: base_(nullptr),
clock_(nullptr),
graph_(nullptr),
Expand All @@ -74,13 +74,13 @@ class NodeHandle : public std::enable_shared_from_this<NodeHandle<InterfaceTs...
* Additionally, to bind all interfaces, specify AllInterfaces.
*
* For example:
* - ```NodeHandle<>(node)``` will bind no interfaces.
* - ```NodeHandle<BaseInterface>(node)``` will bind just the NodeBaseInterface.
* - ```NodeHandle<AllInterfaces>(node)``` will bind all interfaces.
* - ```NodeInterfaceHandle<>(node)``` will bind no interfaces.
* - ```NodeInterfaceHandle<BaseInterface>(node)``` will bind just the NodeBaseInterface.
* - ```NodeInterfaceHandle<AllInterfaces>(node)``` will bind all interfaces.
* \param[in] node Node-like object to bind the interfaces of.
*/
template<typename NodeT>
explicit NodeHandle(const NodeT & node)
explicit NodeInterfaceHandle(const NodeT & node)
{
if constexpr (0 == sizeof ...(InterfaceTs)) {
base_ = nullptr;
Expand Down Expand Up @@ -237,7 +237,10 @@ class NodeHandle : public std::enable_shared_from_this<NodeHandle<InterfaceTs...

/// Create a new node handle bound with no node interfaces.
RCLCPP_PUBLIC
inline NodeHandle<>::SharedPtr get_node_handle() {return std::make_shared<NodeHandle<>>();}
inline NodeInterfaceHandle<>::SharedPtr get_node_handle()
{
return std::make_shared<NodeInterfaceHandle<>>();
}


/// Create a new node handle bound with the passed in node-like object's interfaces.
Expand All @@ -248,10 +251,10 @@ inline NodeHandle<>::SharedPtr get_node_handle() {return std::make_shared<NodeHa
* \param[in] node Node-like object to bind the interfaces of.
*/
template<typename NodeT>
typename NodeHandle<>::SharedPtr
typename NodeInterfaceHandle<>::SharedPtr
get_node_handle(const NodeT & node)
{
return std::make_shared<NodeHandle<>>(node);
return std::make_shared<NodeInterfaceHandle<>>(node);
}


Expand All @@ -260,18 +263,18 @@ get_node_handle(const NodeT & node)
* You may specify in the template parameters the interfaces to bind. Any unbound interfaces
* will be nullptr.
*
* For example: ```NodeHandle<BaseInterface>(node)``` will bind just the NodeBaseInterface.
* For example: ```NodeInterfaceHandle<BaseInterface>(node)``` will bind just the NodeBaseInterface.
*
* \param[in] node Node-like object to bind the interfaces of.
*/
template<typename ... InterfaceTs, typename NodeT>
typename NodeHandle<InterfaceTs...>::SharedPtr
typename NodeInterfaceHandle<InterfaceTs...>::SharedPtr
get_node_handle(const NodeT & node)
{
if constexpr (0 == sizeof...(InterfaceTs)) {
return get_node_handle(node);
} else {
return std::make_shared<NodeHandle<InterfaceTs...>>(node);
return std::make_shared<NodeInterfaceHandle<InterfaceTs...>>(node);
}
}

Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -395,10 +395,10 @@ Node::get_parameters(
}

template<typename ... InterfaceTs>
typename rclcpp::NodeHandle<InterfaceTs...>::SharedPtr
typename rclcpp::NodeInterfaceHandle<InterfaceTs...>::SharedPtr
Node::get_node_handle()
{
return std::make_shared<rclcpp::NodeHandle<InterfaceTs...>>(this);
return std::make_shared<rclcpp::NodeInterfaceHandle<InterfaceTs...>>(this);
}

} // namespace rclcpp
Expand Down
59 changes: 32 additions & 27 deletions rclcpp/test/rclcpp/test_node_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,15 @@
#include "rclcpp/node.hpp"
#include "rclcpp/node_handle.hpp"

class TestNodeHandle : public ::testing::Test
class TestNodeInterfaceHandle : public ::testing::Test
{
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}


static void TearDownTestCase()
{
rclcpp::shutdown();
Expand All @@ -33,11 +34,11 @@ class TestNodeHandle : public ::testing::Test
/*
Testing node handle construction.
*/
TEST_F(TestNodeHandle, nh_init) {
TEST_F(TestNodeInterfaceHandle, nh_init) {
{
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");

auto empty_nh = std::make_shared<rclcpp::NodeHandle<>>();
auto empty_nh = std::make_shared<rclcpp::NodeInterfaceHandle<>>();
EXPECT_EQ(nullptr, empty_nh->base());
EXPECT_EQ(nullptr, empty_nh->clock());
EXPECT_EQ(nullptr, empty_nh->graph());
Expand All @@ -61,7 +62,7 @@ TEST_F(TestNodeHandle, nh_init) {
EXPECT_EQ(nullptr, empty_nh_from_standalone->parameters());
EXPECT_EQ(nullptr, empty_nh_from_standalone->time_source());

auto base_nh = std::make_shared<rclcpp::NodeHandle<rclcpp::BaseInterface>>(node);
auto base_nh = std::make_shared<rclcpp::NodeInterfaceHandle<rclcpp::BaseInterface>>(node);
EXPECT_NE(nullptr, base_nh->base());
EXPECT_STREQ("my_node", base_nh->base()->get_name());
EXPECT_EQ(nullptr, base_nh->clock());
Expand All @@ -88,7 +89,10 @@ TEST_F(TestNodeHandle, nh_init) {
EXPECT_EQ(nullptr, base_nh_from_standalone->time_source());

auto base_clock_nh =
std::make_shared<rclcpp::NodeHandle<rclcpp::BaseInterface, rclcpp::ClockInterface>>(node);
std::make_shared<rclcpp::NodeInterfaceHandle<
rclcpp::BaseInterface,
rclcpp::ClockInterface
>>(node);
EXPECT_NE(nullptr, base_clock_nh->base());
EXPECT_STREQ("my_node", base_clock_nh->base()->get_name());
EXPECT_NE(nullptr, base_clock_nh->clock());
Expand All @@ -103,7 +107,7 @@ TEST_F(TestNodeHandle, nh_init) {
EXPECT_EQ(nullptr, base_clock_nh->time_source());

auto sans_base_clock_nh = std::make_shared<
rclcpp::NodeHandle<
rclcpp::NodeInterfaceHandle<
rclcpp::GraphInterface,
rclcpp::LoggingInterface,
rclcpp::TimersInterface,
Expand All @@ -124,7 +128,7 @@ TEST_F(TestNodeHandle, nh_init) {
EXPECT_NE(nullptr, sans_base_clock_nh->parameters());
EXPECT_NE(nullptr, sans_base_clock_nh->time_source());

auto all_nh = std::make_shared<rclcpp::NodeHandle<rclcpp::AllInterfaces>>(node);
auto all_nh = std::make_shared<rclcpp::NodeInterfaceHandle<rclcpp::AllInterfaces>>(node);
EXPECT_NE(nullptr, all_nh->base());
EXPECT_NE(nullptr, all_nh->clock());
EXPECT_NE(nullptr, all_nh->graph());
Expand All @@ -136,7 +140,7 @@ TEST_F(TestNodeHandle, nh_init) {
EXPECT_NE(nullptr, all_nh->parameters());
EXPECT_NE(nullptr, all_nh->time_source());

auto empty_nh_from_node = std::make_shared<rclcpp::NodeHandle<>>(node);
auto empty_nh_from_node = std::make_shared<rclcpp::NodeInterfaceHandle<>>(node);
EXPECT_EQ(nullptr, empty_nh_from_node->base());
EXPECT_EQ(nullptr, empty_nh_from_node->clock());
EXPECT_EQ(nullptr, empty_nh_from_node->graph());
Expand All @@ -153,11 +157,11 @@ TEST_F(TestNodeHandle, nh_init) {
/*
Testing node handle construction with alternate getters.
*/
TEST_F(TestNodeHandle, nh_init_alternate_getters) {
TEST_F(TestNodeInterfaceHandle, nh_init_alternate_getters) {
{
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");

auto base_nh = std::make_shared<rclcpp::NodeHandle<rclcpp::BaseInterface>>(node);
auto base_nh = std::make_shared<rclcpp::NodeInterfaceHandle<rclcpp::BaseInterface>>(node);

EXPECT_NE(nullptr, base_nh->get_node_base_interface());
EXPECT_STREQ("my_node", base_nh->get_node_base_interface()->get_name());
Expand All @@ -172,8 +176,10 @@ TEST_F(TestNodeHandle, nh_init_alternate_getters) {
EXPECT_EQ(nullptr, base_nh->get_node_parameters_interface());
EXPECT_EQ(nullptr, base_nh->get_node_time_source_interface());

auto base_clock_nh =
std::make_shared<rclcpp::NodeHandle<rclcpp::BaseInterface, rclcpp::ClockInterface>>(node);
auto base_clock_nh = std::make_shared<rclcpp::NodeInterfaceHandle<
rclcpp::BaseInterface,
rclcpp::ClockInterface
>>(node);

EXPECT_NE(nullptr, base_clock_nh->get_node_base_interface());
EXPECT_STREQ("my_node", base_clock_nh->get_node_base_interface()->get_name());
Expand All @@ -191,17 +197,16 @@ TEST_F(TestNodeHandle, nh_init_alternate_getters) {
EXPECT_EQ(nullptr, base_clock_nh->get_node_parameters_interface());
EXPECT_EQ(nullptr, base_clock_nh->get_node_time_source_interface());

auto sans_base_clock_nh = std::make_shared<
rclcpp::NodeHandle<
rclcpp::GraphInterface,
rclcpp::LoggingInterface,
rclcpp::TimersInterface,
rclcpp::TopicsInterface,
rclcpp::ServicesInterface,
rclcpp::WaitablesInterface,
rclcpp::ParametersInterface,
rclcpp::TimeSourceInterface
>>(node);
auto sans_base_clock_nh = std::make_shared<rclcpp::NodeInterfaceHandle<
rclcpp::GraphInterface,
rclcpp::LoggingInterface,
rclcpp::TimersInterface,
rclcpp::TopicsInterface,
rclcpp::ServicesInterface,
rclcpp::WaitablesInterface,
rclcpp::ParametersInterface,
rclcpp::TimeSourceInterface
>>(node);

EXPECT_EQ(nullptr, sans_base_clock_nh->get_node_base_interface());
EXPECT_EQ(nullptr, sans_base_clock_nh->get_node_clock_interface());
Expand All @@ -219,11 +224,11 @@ TEST_F(TestNodeHandle, nh_init_alternate_getters) {
/*
Testing node handle setters.
*/
TEST_F(TestNodeHandle, nh_setters) {
TEST_F(TestNodeInterfaceHandle, nh_setters) {
{
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");

auto base_nh = std::make_shared<rclcpp::NodeHandle<rclcpp::BaseInterface>>(node);
auto base_nh = std::make_shared<rclcpp::NodeInterfaceHandle<rclcpp::BaseInterface>>(node);

EXPECT_NE(nullptr, base_nh->base());
EXPECT_STREQ("my_node", base_nh->base()->get_name());
Expand All @@ -241,11 +246,11 @@ TEST_F(TestNodeHandle, nh_setters) {
/*
Testing node handle alternate setters.
*/
TEST_F(TestNodeHandle, nh_alternate_setters) {
TEST_F(TestNodeInterfaceHandle, nh_alternate_setters) {
{
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");

auto base_nh = std::make_shared<rclcpp::NodeHandle<rclcpp::BaseInterface>>(node);
auto base_nh = std::make_shared<rclcpp::NodeInterfaceHandle<rclcpp::BaseInterface>>(node);

EXPECT_NE(nullptr, base_nh->base());
EXPECT_STREQ("my_node", base_nh->base()->get_name());
Expand Down
17 changes: 10 additions & 7 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -823,19 +823,22 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
get_node_waitables_interface();

/// Return a NodeHandle bound with the LifecycleNode's internal node interfaces.
/// Return a NodeInterfaceHandle bound with the LifecycleNode's internal node interfaces.
/**
* This overload binds all interfaces, if you want to bind a subset of interfaces, specify them
* in the template parameters of the templated method.
*
* \return a NodeHandle bound with the LifecycleNode's internal node interfaces.
* \return a NodeInterfaceHandle bound with the LifecycleNode's internal node interfaces.
*/
RCLCPP_LIFECYCLE_PUBLIC
inline
rclcpp::NodeHandle<rclcpp::AllInterfaces>::SharedPtr
get_node_handle() {return std::make_shared<rclcpp::NodeHandle<rclcpp::AllInterfaces>>(this);}
rclcpp::NodeInterfaceHandle<rclcpp::AllInterfaces>::SharedPtr
get_node_handle()
{
return std::make_shared<rclcpp::NodeInterfaceHandle<rclcpp::AllInterfaces>>(this);
}

/// Return a NodeHandle bound with the LifecycleNode's internal node interfaces.
/// Return a NodeInterfaceHandle bound with the LifecycleNode's internal node interfaces.
/**
* Specify which interfaces you want to bind using the temlplate parameters. Any unbound
* interfaces will be nullptr.
Expand All @@ -850,10 +853,10 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
* - ```node->get_node_handle<AllInterfaces>()``` will bind all interfaces.
* - ```node->get_node_handle()``` will bind all interfaces.
*
* \return a NodeHandle bound with the LifecycleNode's internal node interfaces.
* \return a NodeInterfaceHandle bound with the LifecycleNode's internal node interfaces.
*/
template<typename ... InterfaceTs>
typename rclcpp::NodeHandle<InterfaceTs...>::SharedPtr
typename rclcpp::NodeInterfaceHandle<InterfaceTs...>::SharedPtr
get_node_handle();

/// Return the NodeOptions used when creating this node.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -333,10 +333,10 @@ LifecycleNode::get_parameter_or(
}

template<typename ... InterfaceTs>
typename rclcpp::NodeHandle<InterfaceTs...>::SharedPtr
typename rclcpp::NodeInterfaceHandle<InterfaceTs...>::SharedPtr
LifecycleNode::get_node_handle()
{
return std::make_shared<rclcpp::NodeHandle<InterfaceTs...>>(this);
return std::make_shared<rclcpp::NodeInterfaceHandle<InterfaceTs...>>(this);
}

} // namespace rclcpp_lifecycle
Expand Down

0 comments on commit 6734ecf

Please sign in to comment.