Skip to content

Commit

Permalink
Made rmw_qos_profile argument optional
Browse files Browse the repository at this point in the history
  • Loading branch information
Esteve Fernandez committed Oct 19, 2015
1 parent 1d5720f commit 4151bcb
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 10 deletions.
13 changes: 7 additions & 6 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,13 +112,14 @@ class Node
template<typename MessageT>
typename rclcpp::publisher::Publisher<MessageT>::SharedPtr
create_publisher(
const std::string & topic_name, const rmw_qos_profile_t & qos_profile);
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default);

/// Create and return a Subscription.
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] qos_profile The quality of service profile to pass on to the rmw implementation.
* \param[in] callback The user-defined callback function.
* \param[in] qos_profile The quality of service profile to pass on to the rmw implementation.
* \param[in] group The callback group for this subscription. NULL for no callback group.
* \param[in] ignore_local_publications True to ignore local publications.
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
Expand All @@ -131,9 +132,9 @@ class Node
template<typename MessageT, typename CallbackT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
create_subscription(
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile,
CallbackT callback,
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
bool ignore_local_publications = false,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
Expand All @@ -142,8 +143,8 @@ class Node
/// Create and return a Subscription.
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] qos_history_depth The depth of the subscription's incoming message queue.
* \param[in] callback The user-defined callback function.
* \param[in] qos_history_depth The depth of the subscription's incoming message queue.
* \param[in] group The callback group for this subscription. NULL for no callback group.
* \param[in] ignore_local_publications True to ignore local publications.
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
Expand All @@ -156,9 +157,9 @@ class Node
template<typename MessageT, typename CallbackT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
create_subscription(
CallbackT callback,
const std::string & topic_name,
size_t qos_history_depth,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
bool ignore_local_publications = false,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,9 +208,9 @@ Node::group_in_node(callback_group::CallbackGroup::SharedPtr group)
template<typename MessageT, typename CallbackT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
Node::create_subscription(
CallbackT callback,
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
Expand Down Expand Up @@ -309,9 +309,9 @@ Node::create_subscription(
template<typename MessageT, typename CallbackT>
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
Node::create_subscription(
CallbackT callback,
const std::string & topic_name,
size_t qos_history_depth,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
Expand All @@ -320,9 +320,9 @@ Node::create_subscription(
rmw_qos_profile_t qos = rmw_qos_profile_default;
qos.depth = qos_history_depth;
return this->create_subscription<MessageT, CallbackT>(
callback,
topic_name,
qos,
callback,
group,
ignore_local_publications,
msg_mem_strat);
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ class AsyncParametersClient
on_parameter_event(FunctorT callback)
{
return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>(
"parameter_events", rmw_qos_profile_parameter_events, callback);
callback, "parameter_events", rmw_qos_profile_parameter_events);
}

private:
Expand Down

0 comments on commit 4151bcb

Please sign in to comment.