Skip to content

Commit

Permalink
Get logger name from rcl [indirect]
Browse files Browse the repository at this point in the history
  • Loading branch information
dhood committed Jan 23, 2018
1 parent c440b08 commit 88af1f2
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 1 deletion.
5 changes: 5 additions & 0 deletions rclcpp/include/rclcpp/node_interfaces/node_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,11 @@ class NodeBase : public NodeBaseInterface
const char *
get_namespace() const;

RCLCPP_PUBLIC
virtual
const char *
get_logger_name() const;

RCLCPP_PUBLIC
virtual
rclcpp::Context::SharedPtr
Expand Down
7 changes: 7 additions & 0 deletions rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,13 @@ class NodeBaseInterface
const char *
get_namespace() const = 0;

/// Return the logger name associated with the node.
/** \return The namespace of the node. */
RCLCPP_PUBLIC
virtual
const char *
get_logger_name() const = 0;

/// Return the context of the node.
/** \return SharedPtr to the node's context. */
RCLCPP_PUBLIC
Expand Down
6 changes: 6 additions & 0 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,12 @@ NodeBase::get_namespace() const
return rcl_node_get_namespace(node_handle_.get());
}

const char *
NodeBase::get_logger_name() const
{
return rcl_node_get_logger_name(node_handle_.get());
}

rclcpp::Context::SharedPtr
NodeBase::get_context()
{
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ using rclcpp::node_interfaces::NodeLogging;
NodeLogging::NodeLogging(rclcpp::node_interfaces::NodeBaseInterface * node_base)
: node_base_(node_base)
{
logger_ = rclcpp::get_logger(rcl_node_get_logger_name(node_base_->get_rcl_node_handle()));
logger_ = rclcpp::get_logger(node_base->get_logger_name());
}

NodeLogging::~NodeLogging()
Expand Down

0 comments on commit 88af1f2

Please sign in to comment.