Skip to content

Commit

Permalink
Merge pull request #71 from ros2/qos
Browse files Browse the repository at this point in the history
Added support for QoS profiles
  • Loading branch information
esteve committed Aug 7, 2015
2 parents 3f2df48 + 90f71aa commit a4154a2
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 14 deletions.
5 changes: 3 additions & 2 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,8 @@ class Node
/* Create and return a Publisher. */
template<typename MessageT>
rclcpp::publisher::Publisher::SharedPtr
create_publisher(const std::string & topic_name, size_t queue_size);
create_publisher(
const std::string & topic_name, const rmw_qos_profile_t & qos_profile);

/* Create and return a Subscription. */

Expand All @@ -130,7 +131,7 @@ class Node
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
create_subscription(
const std::string & topic_name,
size_t queue_size,
const rmw_qos_profile_t & qos_profile,
std::function<void(const std::shared_ptr<MessageT> &)> callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
bool ignore_local_publications = false,
Expand Down
18 changes: 9 additions & 9 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,11 +76,10 @@ Node::Node(const std::string & node_name, context::Context::SharedPtr context)
});

using rclcpp::callback_group::CallbackGroupType;
default_callback_group_ =
create_callback_group(CallbackGroupType::MutuallyExclusive);
// TODO(esteve): remove hardcoded values
events_publisher_ =
create_publisher<rcl_interfaces::msg::ParameterEvent>("parameter_events", 1000);
default_callback_group_ = create_callback_group(
CallbackGroupType::MutuallyExclusive);
events_publisher_ = create_publisher<rcl_interfaces::msg::ParameterEvent>(
"parameter_events", rmw_qos_profile_parameter_events);
}

rclcpp::callback_group::CallbackGroup::SharedPtr
Expand All @@ -96,12 +95,13 @@ Node::create_callback_group(

template<typename MessageT>
publisher::Publisher::SharedPtr
Node::create_publisher(const std::string & topic_name, size_t queue_size)
Node::create_publisher(
const std::string & topic_name, const rmw_qos_profile_t & qos_profile)
{
using rosidl_generator_cpp::get_message_type_support_handle;
auto type_support_handle = get_message_type_support_handle<MessageT>();
rmw_publisher_t * publisher_handle = rmw_create_publisher(
node_handle_.get(), type_support_handle, topic_name.c_str(), queue_size);
node_handle_.get(), type_support_handle, topic_name.c_str(), qos_profile);
if (!publisher_handle) {
// *INDENT-OFF* (prevent uncrustify from making unecessary indents here)
throw std::runtime_error(
Expand Down Expand Up @@ -130,7 +130,7 @@ template<typename MessageT>
typename subscription::Subscription<MessageT>::SharedPtr
Node::create_subscription(
const std::string & topic_name,
size_t queue_size,
const rmw_qos_profile_t & qos_profile,
std::function<void(const std::shared_ptr<MessageT> &)> callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
Expand All @@ -146,7 +146,7 @@ Node::create_subscription(
auto type_support_handle = get_message_type_support_handle<MessageT>();
rmw_subscription_t * subscriber_handle = rmw_create_subscription(
node_handle_.get(), type_support_handle,
topic_name.c_str(), queue_size, ignore_local_publications);
topic_name.c_str(), qos_profile, ignore_local_publications);
if (!subscriber_handle) {
// *INDENT-OFF* (prevent uncrustify from making unecessary indents here)
throw std::runtime_error(
Expand Down
5 changes: 2 additions & 3 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -231,9 +231,8 @@ class AsyncParametersClient
typename rclcpp::subscription::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
on_parameter_event(FunctorT & callback)
{
// TODO(esteve): remove hardcoded values
return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>("parameter_events",
1000, callback);
return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>(
"parameter_events", rmw_qos_profile_parameter_events, callback);
}

private:
Expand Down

0 comments on commit a4154a2

Please sign in to comment.