Made rmw_qos_profile argument optional
This commit is contained in:
parent
1d5720f964
commit
c845e9bd45
3 changed files with 7 additions and 6 deletions
|
@ -112,13 +112,14 @@ public:
|
||||||
template<typename MessageT>
|
template<typename MessageT>
|
||||||
typename rclcpp::publisher::Publisher<MessageT>::SharedPtr
|
typename rclcpp::publisher::Publisher<MessageT>::SharedPtr
|
||||||
create_publisher(
|
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.
|
/// Create and return a Subscription.
|
||||||
/**
|
/**
|
||||||
* \param[in] topic_name The topic to subscribe on.
|
* \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] 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] group The callback group for this subscription. NULL for no callback group.
|
||||||
* \param[in] ignore_local_publications True to ignore local publications.
|
* \param[in] ignore_local_publications True to ignore local publications.
|
||||||
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
|
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
|
||||||
|
@ -132,8 +133,8 @@ public:
|
||||||
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
|
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
|
||||||
create_subscription(
|
create_subscription(
|
||||||
const std::string & topic_name,
|
const std::string & topic_name,
|
||||||
const rmw_qos_profile_t & qos_profile,
|
|
||||||
CallbackT callback,
|
CallbackT callback,
|
||||||
|
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
||||||
bool ignore_local_publications = false,
|
bool ignore_local_publications = false,
|
||||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
|
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
|
||||||
|
|
|
@ -209,8 +209,8 @@ template<typename MessageT, typename CallbackT>
|
||||||
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
|
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
|
||||||
Node::create_subscription(
|
Node::create_subscription(
|
||||||
const std::string & topic_name,
|
const std::string & topic_name,
|
||||||
const rmw_qos_profile_t & qos_profile,
|
|
||||||
CallbackT callback,
|
CallbackT callback,
|
||||||
|
const rmw_qos_profile_t & qos_profile,
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
||||||
bool ignore_local_publications,
|
bool ignore_local_publications,
|
||||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
|
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
|
||||||
|
@ -321,8 +321,8 @@ Node::create_subscription(
|
||||||
qos.depth = qos_history_depth;
|
qos.depth = qos_history_depth;
|
||||||
return this->create_subscription<MessageT, CallbackT>(
|
return this->create_subscription<MessageT, CallbackT>(
|
||||||
topic_name,
|
topic_name,
|
||||||
qos,
|
|
||||||
callback,
|
callback,
|
||||||
|
qos,
|
||||||
group,
|
group,
|
||||||
ignore_local_publications,
|
ignore_local_publications,
|
||||||
msg_mem_strat);
|
msg_mem_strat);
|
||||||
|
|
|
@ -232,7 +232,7 @@ public:
|
||||||
on_parameter_event(FunctorT callback)
|
on_parameter_event(FunctorT callback)
|
||||||
{
|
{
|
||||||
return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>(
|
return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>(
|
||||||
"parameter_events", rmw_qos_profile_parameter_events, callback);
|
"parameter_events", callback, rmw_qos_profile_parameter_events);
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue