Merge pull request #100 from ros2/remove_reference_for_smart_pointer

remove references on smart pointers
This commit is contained in:
Dirk Thomas 2015-08-28 14:53:17 -07:00
commit 8de48c5c0d
9 changed files with 35 additions and 35 deletions

View file

@ -63,25 +63,25 @@ private:
void void
add_subscription( add_subscription(
const subscription::SubscriptionBase::SharedPtr & subscription_ptr) const subscription::SubscriptionBase::SharedPtr subscription_ptr)
{ {
subscription_ptrs_.push_back(subscription_ptr); subscription_ptrs_.push_back(subscription_ptr);
} }
void void
add_timer(const timer::TimerBase::SharedPtr & timer_ptr) add_timer(const timer::TimerBase::SharedPtr timer_ptr)
{ {
timer_ptrs_.push_back(timer_ptr); timer_ptrs_.push_back(timer_ptr);
} }
void void
add_service(const service::ServiceBase::SharedPtr & service_ptr) add_service(const service::ServiceBase::SharedPtr service_ptr)
{ {
service_ptrs_.push_back(service_ptr); service_ptrs_.push_back(service_ptr);
} }
void void
add_client(const client::ClientBase::SharedPtr & client_ptr) add_client(const client::ClientBase::SharedPtr client_ptr)
{ {
client_ptrs_.push_back(client_ptr); client_ptrs_.push_back(client_ptr);
} }

View file

@ -136,13 +136,13 @@ public:
} }
SharedFuture async_send_request( SharedFuture async_send_request(
typename ServiceT::Request::SharedPtr & request) typename ServiceT::Request::SharedPtr request)
{ {
return async_send_request(request, [](SharedFuture) {}); return async_send_request(request, [](SharedFuture) {});
} }
SharedFuture async_send_request( SharedFuture async_send_request(
typename ServiceT::Request::SharedPtr & request, typename ServiceT::Request::SharedPtr request,
CallbackType cb) CallbackType cb)
{ {
int64_t sequence_number; int64_t sequence_number;

View file

@ -116,7 +116,7 @@ public:
* waiting for work in another thread, because otherwise the executor would never be notified. * waiting for work in another thread, because otherwise the executor would never be notified.
*/ */
virtual void virtual void
remove_node(rclcpp::node::Node::SharedPtr & node_ptr, bool notify = true) remove_node(rclcpp::node::Node::SharedPtr node_ptr, bool notify = true)
{ {
bool node_removed = false; bool node_removed = false;
weak_nodes_.erase( weak_nodes_.erase(
@ -147,7 +147,7 @@ public:
* function to be non-blocking. * function to be non-blocking.
*/ */
template<typename T = std::milli> template<typename T = std::milli>
void spin_node_once(rclcpp::node::Node::SharedPtr & node, void spin_node_once(rclcpp::node::Node::SharedPtr node,
std::chrono::duration<int64_t, T> timeout = std::chrono::duration<int64_t, T>(-1)) std::chrono::duration<int64_t, T> timeout = std::chrono::duration<int64_t, T>(-1))
{ {
this->add_node(node, false); this->add_node(node, false);
@ -163,7 +163,7 @@ public:
/** /**
* \param[in] node Shared pointer to the node to add. * \param[in] node Shared pointer to the node to add.
*/ */
void spin_node_some(rclcpp::node::Node::SharedPtr & node) void spin_node_some(rclcpp::node::Node::SharedPtr node)
{ {
this->add_node(node, false); this->add_node(node, false);
spin_some(); spin_some();
@ -207,7 +207,7 @@ protected:
* service, client). * service, client).
*/ */
void void
execute_any_executable(AnyExecutable::SharedPtr & any_exec) execute_any_executable(AnyExecutable::SharedPtr any_exec)
{ {
if (!any_exec) { if (!any_exec) {
return; return;
@ -239,7 +239,7 @@ protected:
static void static void
execute_subscription( execute_subscription(
rclcpp::subscription::SubscriptionBase::SharedPtr & subscription) rclcpp::subscription::SubscriptionBase::SharedPtr subscription)
{ {
std::shared_ptr<void> message = subscription->create_message(); std::shared_ptr<void> message = subscription->create_message();
bool taken = false; bool taken = false;
@ -261,7 +261,7 @@ protected:
static void static void
execute_intra_process_subscription( execute_intra_process_subscription(
rclcpp::subscription::SubscriptionBase::SharedPtr & subscription) rclcpp::subscription::SubscriptionBase::SharedPtr subscription)
{ {
rcl_interfaces::msg::IntraProcessMessage ipm; rcl_interfaces::msg::IntraProcessMessage ipm;
bool taken = false; bool taken = false;
@ -285,14 +285,14 @@ protected:
static void static void
execute_timer( execute_timer(
rclcpp::timer::TimerBase::SharedPtr & timer) rclcpp::timer::TimerBase::SharedPtr timer)
{ {
timer->callback_(); timer->callback_();
} }
static void static void
execute_service( execute_service(
rclcpp::service::ServiceBase::SharedPtr & service) rclcpp::service::ServiceBase::SharedPtr service)
{ {
std::shared_ptr<void> request_header = service->create_request_header(); std::shared_ptr<void> request_header = service->create_request_header();
std::shared_ptr<void> request = service->create_request(); std::shared_ptr<void> request = service->create_request();
@ -315,7 +315,7 @@ protected:
static void static void
execute_client( execute_client(
rclcpp::client::ClientBase::SharedPtr & client) rclcpp::client::ClientBase::SharedPtr client)
{ {
std::shared_ptr<void> request_header = client->create_request_header(); std::shared_ptr<void> request_header = client->create_request_header();
std::shared_ptr<void> response = client->create_response(); std::shared_ptr<void> response = client->create_response();
@ -623,7 +623,7 @@ protected:
} }
rclcpp::node::Node::SharedPtr rclcpp::node::Node::SharedPtr
get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr & group) get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group)
{ {
if (!group) { if (!group) {
return rclcpp::node::Node::SharedPtr(); return rclcpp::node::Node::SharedPtr();
@ -645,7 +645,7 @@ protected:
rclcpp::callback_group::CallbackGroup::SharedPtr rclcpp::callback_group::CallbackGroup::SharedPtr
get_group_by_timer( get_group_by_timer(
rclcpp::timer::TimerBase::SharedPtr & timer) rclcpp::timer::TimerBase::SharedPtr timer)
{ {
for (auto & weak_node : weak_nodes_) { for (auto & weak_node : weak_nodes_) {
auto node = weak_node.lock(); auto node = weak_node.lock();
@ -669,7 +669,7 @@ protected:
} }
void void
get_next_timer(AnyExecutable::SharedPtr & any_exec) get_next_timer(AnyExecutable::SharedPtr any_exec)
{ {
for (auto & weak_node : weak_nodes_) { for (auto & weak_node : weak_nodes_) {
auto node = weak_node.lock(); auto node = weak_node.lock();
@ -727,7 +727,7 @@ protected:
rclcpp::callback_group::CallbackGroup::SharedPtr rclcpp::callback_group::CallbackGroup::SharedPtr
get_group_by_subscription( get_group_by_subscription(
rclcpp::subscription::SubscriptionBase::SharedPtr & subscription) rclcpp::subscription::SubscriptionBase::SharedPtr subscription)
{ {
for (auto & weak_node : weak_nodes_) { for (auto & weak_node : weak_nodes_) {
auto node = weak_node.lock(); auto node = weak_node.lock();
@ -751,7 +751,7 @@ protected:
} }
void void
get_next_subscription(AnyExecutable::SharedPtr & any_exec) get_next_subscription(AnyExecutable::SharedPtr any_exec)
{ {
auto it = subscriber_handles_.begin(); auto it = subscriber_handles_.begin();
while (it != subscriber_handles_.end()) { while (it != subscriber_handles_.end()) {
@ -794,7 +794,7 @@ protected:
rclcpp::callback_group::CallbackGroup::SharedPtr rclcpp::callback_group::CallbackGroup::SharedPtr
get_group_by_service( get_group_by_service(
rclcpp::service::ServiceBase::SharedPtr & service) rclcpp::service::ServiceBase::SharedPtr service)
{ {
for (auto & weak_node : weak_nodes_) { for (auto & weak_node : weak_nodes_) {
auto node = weak_node.lock(); auto node = weak_node.lock();
@ -817,7 +817,7 @@ protected:
} }
void void
get_next_service(AnyExecutable::SharedPtr & any_exec) get_next_service(AnyExecutable::SharedPtr any_exec)
{ {
auto it = service_handles_.begin(); auto it = service_handles_.begin();
while (it != service_handles_.end()) { while (it != service_handles_.end()) {
@ -851,7 +851,7 @@ protected:
rclcpp::callback_group::CallbackGroup::SharedPtr rclcpp::callback_group::CallbackGroup::SharedPtr
get_group_by_client( get_group_by_client(
rclcpp::client::ClientBase::SharedPtr & client) rclcpp::client::ClientBase::SharedPtr client)
{ {
for (auto & weak_node : weak_nodes_) { for (auto & weak_node : weak_nodes_) {
auto node = weak_node.lock(); auto node = weak_node.lock();
@ -874,7 +874,7 @@ protected:
} }
void void
get_next_client(AnyExecutable::SharedPtr & any_exec) get_next_client(AnyExecutable::SharedPtr any_exec)
{ {
auto it = client_handles_.begin(); auto it = client_handles_.begin();
while (it != client_handles_.end()) { while (it != client_handles_.end()) {

View file

@ -32,7 +32,7 @@ using rclcpp::executors::single_threaded_executor::SingleThreadedExecutor;
template<typename FutureT> template<typename FutureT>
std::shared_future<FutureT> & std::shared_future<FutureT> &
spin_node_until_future_complete( spin_node_until_future_complete(
rclcpp::executor::Executor & executor, rclcpp::node::Node::SharedPtr & node_ptr, rclcpp::executor::Executor & executor, rclcpp::node::Node::SharedPtr node_ptr,
std::shared_future<FutureT> & future) std::shared_future<FutureT> & future)
{ {
std::future_status status; std::future_status status;

View file

@ -213,7 +213,7 @@ private:
static const rosidl_message_type_support_t * ipm_ts_; static const rosidl_message_type_support_t * ipm_ts_;
bool bool
group_in_node(callback_group::CallbackGroup::SharedPtr & group); group_in_node(callback_group::CallbackGroup::SharedPtr group);
std::string name_; std::string name_;

View file

@ -185,7 +185,7 @@ Node::create_publisher(
} }
bool bool
Node::group_in_node(callback_group::CallbackGroup::SharedPtr & group) Node::group_in_node(callback_group::CallbackGroup::SharedPtr group)
{ {
bool group_belongs_to_this_node = false; bool group_belongs_to_this_node = false;
for (auto & weak_group : this->callback_groups_) { for (auto & weak_group : this->callback_groups_) {

View file

@ -46,7 +46,7 @@ class AsyncParametersClient
public: public:
RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient); RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient);
AsyncParametersClient(const rclcpp::node::Node::SharedPtr & node, AsyncParametersClient(const rclcpp::node::Node::SharedPtr node,
const std::string & remote_node_name = "") const std::string & remote_node_name = "")
: node_(node) : node_(node)
{ {
@ -255,7 +255,7 @@ public:
RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient); RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient);
SyncParametersClient( SyncParametersClient(
rclcpp::node::Node::SharedPtr & node) rclcpp::node::Node::SharedPtr node)
: node_(node) : node_(node)
{ {
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>(); executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
@ -263,8 +263,8 @@ public:
} }
SyncParametersClient( SyncParametersClient(
rclcpp::executor::Executor::SharedPtr & executor, rclcpp::executor::Executor::SharedPtr executor,
rclcpp::node::Node::SharedPtr & node) rclcpp::node::Node::SharedPtr node)
: executor_(executor), node_(node) : executor_(executor), node_(node)
{ {
async_parameters_client_ = std::make_shared<AsyncParametersClient>(node); async_parameters_client_ = std::make_shared<AsyncParametersClient>(node);

View file

@ -43,7 +43,7 @@ class ParameterService
public: public:
RCLCPP_SMART_PTR_DEFINITIONS(ParameterService); RCLCPP_SMART_PTR_DEFINITIONS(ParameterService);
ParameterService(const rclcpp::node::Node::SharedPtr & node) ParameterService(const rclcpp::node::Node::SharedPtr node)
: node_(node) : node_(node)
{ {
get_parameters_service_ = node_->create_service<rcl_interfaces::srv::GetParameters>( get_parameters_service_ = node_->create_service<rcl_interfaces::srv::GetParameters>(

View file

@ -82,7 +82,7 @@ using rclcpp::utilities::sleep_for;
/// Create a default single-threaded executor and execute any immediately available work. /// Create a default single-threaded executor and execute any immediately available work.
// \param[in] node_ptr Shared pointer to the node to spin. // \param[in] node_ptr Shared pointer to the node to spin.
void spin_some(Node::SharedPtr & node_ptr) void spin_some(Node::SharedPtr node_ptr)
{ {
rclcpp::executors::SingleThreadedExecutor executor; rclcpp::executors::SingleThreadedExecutor executor;
executor.spin_node_some(node_ptr); executor.spin_node_some(node_ptr);
@ -90,7 +90,7 @@ void spin_some(Node::SharedPtr & node_ptr)
/// Create a default single-threaded executor and spin the specified node. /// Create a default single-threaded executor and spin the specified node.
// \param[in] node_ptr Shared pointer to the node to spin. // \param[in] node_ptr Shared pointer to the node to spin.
void spin(Node::SharedPtr & node_ptr) void spin(Node::SharedPtr node_ptr)
{ {
rclcpp::executors::SingleThreadedExecutor executor; rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node_ptr); executor.add_node(node_ptr);
@ -100,7 +100,7 @@ void spin(Node::SharedPtr & node_ptr)
template<typename FutureT> template<typename FutureT>
std::shared_future<FutureT> & std::shared_future<FutureT> &
spin_until_future_complete( spin_until_future_complete(
Node::SharedPtr & node_ptr, std::shared_future<FutureT> & future) Node::SharedPtr node_ptr, std::shared_future<FutureT> & future)
{ {
rclcpp::executors::SingleThreadedExecutor executor; rclcpp::executors::SingleThreadedExecutor executor;
rclcpp::executors::spin_node_until_future_complete<FutureT>( rclcpp::executors::spin_node_until_future_complete<FutureT>(