Remove namespaces and namespace escalation e.g. node:: (#416)

* Remove publisher:: namespace

* Remove subscription:: namespace

* Remove client:: namespace

* Remove service:: namespace

* Remove parameter_client:: namespace

* Remove parameter_service:: namespace

* Remove rate:: namespace

* Remove timer:: namespace

* Remove node:: namespace

* Remove any_service_callback:: namespace

* Remove any_subscription_callback:: namespace

* Remove event:: namespace

* Remove ContextSharedPtr escalation

Users can use the  directive themselves if they want

* Remove single_threaded_executor:: namespace

* Remove multi_threaded_executor:: namespace

* Remove context:: namespace

* node:: removal from new logger additions

* Fix linter issues that has been triggered with uncrustify

* Remove utilities:: namespace
This commit is contained in:
dhood 2017-12-05 15:02:00 -08:00 committed by GitHub
parent 713ee8059c
commit 6129a12df5
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
83 changed files with 398 additions and 503 deletions

View file

@ -83,7 +83,7 @@ public:
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.
@ -95,7 +95,7 @@ public:
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
@ -172,7 +172,7 @@ public:
typename MessageT,
typename CallbackT,
typename Alloc = std::allocator<void>,
typename SubscriptionT = rclcpp::subscription::Subscription<MessageT, Alloc>>
typename SubscriptionT = rclcpp::Subscription<MessageT, Alloc>>
std::shared_ptr<SubscriptionT>
create_subscription(
const std::string & topic_name,
@ -202,7 +202,7 @@ public:
typename MessageT,
typename CallbackT,
typename Alloc = std::allocator<void>,
typename SubscriptionT = rclcpp::subscription::Subscription<MessageT, Alloc>>
typename SubscriptionT = rclcpp::Subscription<MessageT, Alloc>>
std::shared_ptr<SubscriptionT>
create_subscription(
const std::string & topic_name,
@ -221,7 +221,7 @@ public:
* \param[in] group Callback group to execute this timer's callback in.
*/
template<typename DurationT = std::milli, typename CallbackT>
typename rclcpp::timer::WallTimer<CallbackT>::SharedPtr
typename rclcpp::WallTimer<CallbackT>::SharedPtr
create_wall_timer(
std::chrono::duration<int64_t, DurationT> period,
CallbackT callback,
@ -229,7 +229,7 @@ public:
/* Create and return a Client. */
template<typename ServiceT>
typename rclcpp::client::Client<ServiceT>::SharedPtr
typename rclcpp::Client<ServiceT>::SharedPtr
create_client(
const std::string & service_name,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
@ -237,7 +237,7 @@ public:
/* Create and return a Service. */
template<typename ServiceT, typename CallbackT>
typename rclcpp::service::Service<ServiceT>::SharedPtr
typename rclcpp::Service<ServiceT>::SharedPtr
create_service(
const std::string & service_name,
CallbackT && callback,
@ -313,7 +313,7 @@ public:
* out of scope.
*/
RCLCPP_LIFECYCLE_PUBLIC
rclcpp::event::Event::SharedPtr
rclcpp::Event::SharedPtr
get_graph_event();
/// Wait for a graph event to occur by waiting on an Event to become set.
@ -326,7 +326,7 @@ public:
RCLCPP_LIFECYCLE_PUBLIC
void
wait_for_graph_change(
rclcpp::event::Event::SharedPtr event,
rclcpp::Event::SharedPtr event,
std::chrono::nanoseconds timeout);
RCLCPP_LIFECYCLE_PUBLIC
@ -480,7 +480,7 @@ protected:
RCLCPP_LIFECYCLE_PUBLIC
void
add_timer_handle(std::shared_ptr<rclcpp::timer::TimerBase> timer);
add_timer_handle(std::shared_ptr<rclcpp::TimerBase> timer);
private:
RCLCPP_DISABLE_COPY(LifecycleNode)

View file

@ -90,7 +90,7 @@ LifecycleNode::create_subscription(
return rclcpp::create_subscription<
MessageT, CallbackT, Alloc,
rclcpp::subscription::Subscription<MessageT, Alloc>>(
rclcpp::Subscription<MessageT, Alloc>>(
this->node_topics_.get(),
topic_name,
std::forward<CallbackT>(callback),
@ -131,13 +131,13 @@ LifecycleNode::create_subscription(
}
template<typename DurationT, typename CallbackT>
typename rclcpp::timer::WallTimer<CallbackT>::SharedPtr
typename rclcpp::WallTimer<CallbackT>::SharedPtr
LifecycleNode::create_wall_timer(
std::chrono::duration<int64_t, DurationT> period,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group)
{
auto timer = rclcpp::timer::WallTimer<CallbackT>::make_shared(
auto timer = rclcpp::WallTimer<CallbackT>::make_shared(
std::chrono::duration_cast<std::chrono::nanoseconds>(period),
std::move(callback));
node_timers_->add_timer(timer, group);
@ -145,7 +145,7 @@ LifecycleNode::create_wall_timer(
}
template<typename ServiceT>
typename rclcpp::client::Client<ServiceT>::SharedPtr
typename rclcpp::Client<ServiceT>::SharedPtr
LifecycleNode::create_client(
const std::string & service_name,
const rmw_qos_profile_t & qos_profile,
@ -154,8 +154,8 @@ LifecycleNode::create_client(
rcl_client_options_t options = rcl_client_get_default_options();
options.qos = qos_profile;
using rclcpp::client::Client;
using rclcpp::client::ClientBase;
using rclcpp::Client;
using rclcpp::ClientBase;
auto cli = Client<ServiceT>::make_shared(
node_base_.get(),
@ -169,23 +169,23 @@ LifecycleNode::create_client(
}
template<typename ServiceT, typename CallbackT>
typename rclcpp::service::Service<ServiceT>::SharedPtr
typename rclcpp::Service<ServiceT>::SharedPtr
LifecycleNode::create_service(
const std::string & service_name,
CallbackT && callback,
const rmw_qos_profile_t & qos_profile,
rclcpp::callback_group::CallbackGroup::SharedPtr group)
{
rclcpp::service::AnyServiceCallback<ServiceT> any_service_callback;
rclcpp::AnyServiceCallback<ServiceT> any_service_callback;
any_service_callback.set(std::forward<CallbackT>(callback));
rcl_service_options_t service_options = rcl_service_get_default_options();
service_options.qos = qos_profile;
auto serv = rclcpp::service::Service<ServiceT>::make_shared(
auto serv = rclcpp::Service<ServiceT>::make_shared(
node_base_->get_shared_rcl_node_handle(),
service_name, any_service_callback, service_options);
auto serv_base_ptr = std::dynamic_pointer_cast<rclcpp::service::ServiceBase>(serv);
auto serv_base_ptr = std::dynamic_pointer_cast<rclcpp::ServiceBase>(serv);
node_services_->add_service(serv_base_ptr, group);
return serv;
}

View file

@ -45,7 +45,7 @@ public:
*/
template<typename MessageT, typename Alloc = std::allocator<void>>
class LifecyclePublisher : public LifecyclePublisherInterface,
public rclcpp::publisher::Publisher<MessageT, Alloc>
public rclcpp::Publisher<MessageT, Alloc>
{
public:
using MessageAllocTraits = rclcpp::allocator::AllocRebind<MessageT, Alloc>;
@ -58,7 +58,7 @@ public:
const std::string & topic,
const rcl_publisher_options_t & publisher_options,
std::shared_ptr<MessageAlloc> allocator)
: rclcpp::publisher::Publisher<MessageT, Alloc>(
: rclcpp::Publisher<MessageT, Alloc>(
node_base, topic, publisher_options, allocator),
enabled_(false)
{}
@ -77,7 +77,7 @@ public:
if (!enabled_) {
return;
}
rclcpp::publisher::Publisher<MessageT, Alloc>::publish(msg);
rclcpp::Publisher<MessageT, Alloc>::publish(msg);
}
/// LifecyclePublisher publish function
@ -92,7 +92,7 @@ public:
if (!enabled_) {
return;
}
rclcpp::publisher::Publisher<MessageT, Alloc>::publish(msg);
rclcpp::Publisher<MessageT, Alloc>::publish(msg);
}
/// LifecyclePublisher publish function
@ -107,7 +107,7 @@ public:
if (!enabled_) {
return;
}
rclcpp::publisher::Publisher<MessageT, Alloc>::publish(msg);
rclcpp::Publisher<MessageT, Alloc>::publish(msg);
}
/// LifecyclePublisher publish function
@ -122,7 +122,7 @@ public:
if (!enabled_) {
return;
}
rclcpp::publisher::Publisher<MessageT, Alloc>::publish(msg);
rclcpp::Publisher<MessageT, Alloc>::publish(msg);
}
virtual void
@ -146,7 +146,7 @@ public:
if (!enabled_) {
return;
}
rclcpp::publisher::Publisher<MessageT, Alloc>::publish(msg);
rclcpp::Publisher<MessageT, Alloc>::publish(msg);
}
virtual void

View file

@ -55,7 +55,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())),
@ -209,7 +209,7 @@ LifecycleNode::get_callback_groups() const
return node_base_->get_callback_groups();
}
rclcpp::event::Event::SharedPtr
rclcpp::Event::SharedPtr
LifecycleNode::get_graph_event()
{
return node_graph_->get_graph_event();
@ -217,7 +217,7 @@ LifecycleNode::get_graph_event()
void
LifecycleNode::wait_for_graph_change(
rclcpp::event::Event::SharedPtr event,
rclcpp::Event::SharedPtr event,
std::chrono::nanoseconds timeout)
{
node_graph_->wait_for_graph_change(event, timeout);
@ -449,7 +449,7 @@ LifecycleNode::add_publisher_handle(
}
void
LifecycleNode::add_timer_handle(std::shared_ptr<rclcpp::timer::TimerBase> timer)
LifecycleNode::add_timer_handle(std::shared_ptr<rclcpp::TimerBase> timer)
{
impl_->add_timer_handle(timer);
}

View file

@ -104,61 +104,61 @@ public:
{ // change_state
auto cb = std::bind(&LifecycleNodeInterfaceImpl::on_change_state, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3);
rclcpp::any_service_callback::AnyServiceCallback<ChangeStateSrv> any_cb;
rclcpp::AnyServiceCallback<ChangeStateSrv> any_cb;
any_cb.set(std::move(cb));
srv_change_state_ = std::make_shared<rclcpp::service::Service<ChangeStateSrv>>(
srv_change_state_ = std::make_shared<rclcpp::Service<ChangeStateSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_change_state,
any_cb);
node_services_interface_->add_service(
std::dynamic_pointer_cast<rclcpp::service::ServiceBase>(srv_change_state_),
std::dynamic_pointer_cast<rclcpp::ServiceBase>(srv_change_state_),
nullptr);
}
{ // get_state
auto cb = std::bind(&LifecycleNodeInterfaceImpl::on_get_state, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3);
rclcpp::any_service_callback::AnyServiceCallback<GetStateSrv> any_cb;
rclcpp::AnyServiceCallback<GetStateSrv> any_cb;
any_cb.set(std::move(cb));
srv_get_state_ = std::make_shared<rclcpp::service::Service<GetStateSrv>>(
srv_get_state_ = std::make_shared<rclcpp::Service<GetStateSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_state,
any_cb);
node_services_interface_->add_service(
std::dynamic_pointer_cast<rclcpp::service::ServiceBase>(srv_get_state_),
std::dynamic_pointer_cast<rclcpp::ServiceBase>(srv_get_state_),
nullptr);
}
{ // get_available_states
auto cb = std::bind(&LifecycleNodeInterfaceImpl::on_get_available_states, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3);
rclcpp::any_service_callback::AnyServiceCallback<GetAvailableStatesSrv> any_cb;
rclcpp::AnyServiceCallback<GetAvailableStatesSrv> any_cb;
any_cb.set(std::move(cb));
srv_get_available_states_ = std::make_shared<rclcpp::service::Service<GetAvailableStatesSrv>>(
srv_get_available_states_ = std::make_shared<rclcpp::Service<GetAvailableStatesSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_available_states,
any_cb);
node_services_interface_->add_service(
std::dynamic_pointer_cast<rclcpp::service::ServiceBase>(srv_get_available_states_),
std::dynamic_pointer_cast<rclcpp::ServiceBase>(srv_get_available_states_),
nullptr);
}
{ // get_available_transitions
auto cb = std::bind(&LifecycleNodeInterfaceImpl::on_get_available_transitions, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3);
rclcpp::any_service_callback::AnyServiceCallback<GetAvailableTransitionsSrv> any_cb;
rclcpp::AnyServiceCallback<GetAvailableTransitionsSrv> any_cb;
any_cb.set(std::move(cb));
srv_get_available_transitions_ =
std::make_shared<rclcpp::service::Service<GetAvailableTransitionsSrv>>(
std::make_shared<rclcpp::Service<GetAvailableTransitionsSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_available_transitions,
any_cb);
node_services_interface_->add_service(
std::dynamic_pointer_cast<rclcpp::service::ServiceBase>(srv_get_available_transitions_),
std::dynamic_pointer_cast<rclcpp::ServiceBase>(srv_get_available_transitions_),
nullptr);
}
}
@ -391,7 +391,7 @@ public:
}
void
add_timer_handle(std::shared_ptr<rclcpp::timer::TimerBase> timer)
add_timer_handle(std::shared_ptr<rclcpp::TimerBase> timer)
{
weak_timers_.push_back(timer);
}
@ -404,12 +404,12 @@ public:
using NodeBasePtr = std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>;
using NodeServicesPtr = std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>;
using ChangeStateSrvPtr = std::shared_ptr<rclcpp::service::Service<ChangeStateSrv>>;
using GetStateSrvPtr = std::shared_ptr<rclcpp::service::Service<GetStateSrv>>;
using ChangeStateSrvPtr = std::shared_ptr<rclcpp::Service<ChangeStateSrv>>;
using GetStateSrvPtr = std::shared_ptr<rclcpp::Service<GetStateSrv>>;
using GetAvailableStatesSrvPtr =
std::shared_ptr<rclcpp::service::Service<GetAvailableStatesSrv>>;
std::shared_ptr<rclcpp::Service<GetAvailableStatesSrv>>;
using GetAvailableTransitionsSrvPtr =
std::shared_ptr<rclcpp::service::Service<GetAvailableTransitionsSrv>>;
std::shared_ptr<rclcpp::Service<GetAvailableTransitionsSrv>>;
NodeBasePtr node_base_interface_;
NodeServicesPtr node_services_interface_;
@ -420,7 +420,7 @@ public:
// to controllable things
std::vector<std::weak_ptr<rclcpp_lifecycle::LifecyclePublisherInterface>> weak_pubs_;
std::vector<std::weak_ptr<rclcpp::timer::TimerBase>> weak_timers_;
std::vector<std::weak_ptr<rclcpp::TimerBase>> weak_timers_;
};
} // namespace rclcpp_lifecycle