Skip to content

Commit

Permalink
Remove context:: namespace
Browse files Browse the repository at this point in the history
  • Loading branch information
dhood committed Dec 5, 2017
1 parent 03f9121 commit 0b8041a
Show file tree
Hide file tree
Showing 11 changed files with 15 additions and 19 deletions.
4 changes: 0 additions & 4 deletions rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,6 @@
namespace rclcpp
{

namespace context
{

class Context
{
public:
Expand Down Expand Up @@ -72,7 +69,6 @@ class Context
std::mutex mutex_;
};

} // namespace context
} // namespace rclcpp

#endif // RCLCPP__CONTEXT_HPP_
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/contexts/default_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace contexts
namespace default_context
{

class DefaultContext : public rclcpp::context::Context
class DefaultContext : public rclcpp::Context
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(DefaultContext)
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class Node : public std::enable_shared_from_this<Node>
const std::string & namespace_ = "",
bool use_intra_process_comms = false);

/// Create a node based on the node name and a rclcpp::context::Context.
/// 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.
Expand All @@ -89,7 +89,7 @@ class Node : public std::enable_shared_from_this<Node>
Node(
const std::string & node_name,
const std::string & namespace_,
rclcpp::context::Context::SharedPtr context,
rclcpp::Context::SharedPtr context,
bool use_intra_process_comms = false);

RCLCPP_PUBLIC
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/node_interfaces/node_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class NodeBase : public NodeBaseInterface
NodeBase(
const std::string & node_name,
const std::string & namespace_,
rclcpp::context::Context::SharedPtr context);
rclcpp::Context::SharedPtr context);

RCLCPP_PUBLIC
virtual
Expand All @@ -57,7 +57,7 @@ class NodeBase : public NodeBaseInterface

RCLCPP_PUBLIC
virtual
rclcpp::context::Context::SharedPtr
rclcpp::Context::SharedPtr
get_context();

RCLCPP_PUBLIC
Expand Down Expand Up @@ -118,7 +118,7 @@ class NodeBase : public NodeBaseInterface
private:
RCLCPP_DISABLE_COPY(NodeBase)

rclcpp::context::Context::SharedPtr context_;
rclcpp::Context::SharedPtr context_;

std::shared_ptr<rcl_node_t> node_handle_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class NodeBaseInterface
/** \return SharedPtr to the node's context. */
RCLCPP_PUBLIC
virtual
rclcpp::context::Context::SharedPtr
rclcpp::Context::SharedPtr
get_context() = 0;

/// Return the rcl_node_t node handle (non-const version).
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@
* - rclcpp/strategies/allocator_memory_strategy.hpp
* - rclcpp/strategies/message_pool_memory_strategy.hpp
* - Context object which is shared amongst multiple Nodes:
* - rclcpp::context::Context
* - rclcpp::Context
* - rclcpp/context.hpp
* - rclcpp/contexts/default_context.hpp
* - Various utilities:
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,6 @@

#include "rclcpp/context.hpp"

using rclcpp::context::Context;
using rclcpp::Context;

Context::Context() {}
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ Node::Node(
Node::Node(
const std::string & node_name,
const std::string & namespace_,
rclcpp::context::Context::SharedPtr context,
rclcpp::Context::SharedPtr context,
bool use_intra_process_comms)
: node_base_(new rclcpp::node_interfaces::NodeBase(node_name, namespace_, context)),
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ using rclcpp::node_interfaces::NodeBase;
NodeBase::NodeBase(
const std::string & node_name,
const std::string & namespace_,
rclcpp::context::Context::SharedPtr context)
rclcpp::Context::SharedPtr context)
: context_(context),
node_handle_(nullptr),
default_callback_group_(nullptr),
Expand Down Expand Up @@ -176,7 +176,7 @@ NodeBase::get_namespace() const
return rcl_node_get_namespace(node_handle_.get());
}

rclcpp::context::Context::SharedPtr
rclcpp::Context::SharedPtr
NodeBase::get_context()
{
return context_;
Expand Down
4 changes: 2 additions & 2 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
const std::string & namespace_ = "",
bool use_intra_process_comms = false);

/// Create a node based on the node name and a rclcpp::context::Context.
/// Create a node based on the node name and a rclcpp::Context.
/**
* \param[in] node_name Name of the node.
* \param[in] node_name Namespace of the node.
Expand All @@ -92,7 +92,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
LifecycleNode(
const std::string & node_name,
const std::string & namespace_,
rclcpp::context::Context::SharedPtr context,
rclcpp::Context::SharedPtr context,
bool use_intra_process_comms = false);

RCLCPP_LIFECYCLE_PUBLIC
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_lifecycle/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ LifecycleNode::LifecycleNode(
LifecycleNode::LifecycleNode(
const std::string & node_name,
const std::string & namespace_,
rclcpp::context::Context::SharedPtr context,
rclcpp::Context::SharedPtr context,
bool use_intra_process_comms)
: node_base_(new rclcpp::node_interfaces::NodeBase(node_name, namespace_, context)),
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
Expand Down

0 comments on commit 0b8041a

Please sign in to comment.