Skip to content

Commit

Permalink
use rclcpp::QoS rather than rmw_qos_profile_t
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>
  • Loading branch information
alsora committed Nov 1, 2022
1 parent 9b5dc8c commit f04d164
Show file tree
Hide file tree
Showing 17 changed files with 73 additions and 78 deletions.
2 changes: 1 addition & 1 deletion composition_benchmark/apps/base_publisher_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ std::vector<IRobotNodePtr> create_publisher_node(int argc, char ** argv)
*cli_options.msg_type,
"my_topic",
*cli_options.msg_pass_by,
rmw_qos_profile_default,
rclcpp::SensorDataQoS(),
pub_period,
*cli_options.msg_size);

Expand Down
4 changes: 2 additions & 2 deletions composition_benchmark/apps/multi-producer-node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class MultiProducerNode : public performance_test::PerformanceNode<rclcpp::Node>
using Msg = irobot_interfaces_plugin::msg::Stamped10b;

std::string topic_name = "topic_" + std::to_string(i);
this->add_publisher<Msg>(topic_name, rmw_qos_profile_default);
this->add_publisher<Msg>(topic_name, rclcpp::SensorDataQoS());

auto publish_func = std::bind(
&MultiProducerNode::publish_msg<Msg>,
Expand All @@ -54,7 +54,7 @@ class MultiProducerNode : public performance_test::PerformanceNode<rclcpp::Node>
"slow_topic",
std::chrono::milliseconds(111),
performance_test::msg_pass_by_t::PASS_BY_UNIQUE_PTR,
rmw_qos_profile_default);
rclcpp::SensorDataQoS());
}
};

Expand Down
2 changes: 1 addition & 1 deletion composition_benchmark/src/composable_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ ComposablePublisher::ComposablePublisher(const rclcpp::NodeOptions & options)
topic_name,
period,
performance_test::msg_pass_by_t::PASS_BY_UNIQUE_PTR,
rmw_qos_profile_default,
rclcpp::SensorDataQoS(),
msg_size);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,38 +70,38 @@ class PerformanceNodeBase
msg_pass_by_t msg_pass_by,
performance_metrics::Tracker::Options tracking_options =
performance_metrics::Tracker::Options(),
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
const rclcpp::QoS & qos_profile = rclcpp::SensorDataQoS(),
std::chrono::microseconds work_duration = std::chrono::microseconds::zero());

template<typename Msg>
void add_periodic_publisher(
const std::string & topic_name,
std::chrono::microseconds period,
msg_pass_by_t msg_pass_by,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
const rclcpp::QoS & qos_profile = rclcpp::SensorDataQoS(),
size_t size = 0);

template<typename Msg>
void add_publisher(
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default);
const rclcpp::QoS & qos_profile = rclcpp::SensorDataQoS());

template<typename Srv>
void add_server(
const std::string & service_name,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default);
const rclcpp::QoS & qos_profile = rclcpp::ServicesQoS());

template<typename Srv>
void add_periodic_client(
const std::string & service_name,
std::chrono::microseconds period,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
const rclcpp::QoS & qos_profile = rclcpp::ServicesQoS(),
size_t size = 0);

template<typename Srv>
void add_client(
const std::string & service_name,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default);
const rclcpp::QoS & qos_profile = rclcpp::ServicesQoS());

void add_timer(std::chrono::microseconds period, std::function<void()> callback);

Expand All @@ -125,7 +125,7 @@ class PerformanceNodeBase
const std::string & topic_name,
performance_metrics::Tracker::Options tracking_options =
performance_metrics::Tracker::Options(),
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
const rclcpp::QoS & qos_profile = rclcpp::SensorDataQoS(),
std::chrono::microseconds work_duration = std::chrono::microseconds::zero());

void store_subscription(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ void PerformanceNodeBase::add_subscriber(
const std::string & topic_name,
msg_pass_by_t msg_pass_by,
performance_metrics::Tracker::Options tracking_options,
const rmw_qos_profile_t & qos_profile,
const rclcpp::QoS & qos_profile,
std::chrono::microseconds work_duration)
{
switch (msg_pass_by) {
Expand Down Expand Up @@ -72,24 +72,21 @@ template<
void PerformanceNodeBase::add_subscriber_by_msg_variant(
const std::string & topic_name,
performance_metrics::Tracker::Options tracking_options,
const rmw_qos_profile_t & qos_profile,
const rclcpp::QoS & qos_profile,
std::chrono::microseconds work_duration)
{
rclcpp::SubscriptionBase::SharedPtr sub;
auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile), qos_profile);

std::function<void(CallbackType msg)> callback_function = std::bind(
&PerformanceNodeBase::topic_callback<CallbackType>,
this,
topic_name,
work_duration,
std::placeholders::_1);

sub = rclcpp::create_subscription<Msg>(
rclcpp::SubscriptionBase::SharedPtr sub = rclcpp::create_subscription<Msg>(
m_node_interfaces.parameters,
m_node_interfaces.topics,
topic_name,
qos,
qos_profile,
callback_function);

this->store_subscription(sub, topic_name, tracking_options);
Expand All @@ -100,7 +97,7 @@ void PerformanceNodeBase::add_periodic_publisher(
const std::string & topic_name,
std::chrono::microseconds period,
msg_pass_by_t msg_pass_by,
const rmw_qos_profile_t & qos_profile,
const rclcpp::QoS & qos_profile,
size_t size)
{
this->add_publisher<Msg>(topic_name, qos_profile);
Expand All @@ -119,22 +116,20 @@ void PerformanceNodeBase::add_periodic_publisher(
template<typename Msg>
void PerformanceNodeBase::add_publisher(
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile)
const rclcpp::QoS & qos_profile)
{
auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile), qos_profile);

rclcpp::PublisherBase::SharedPtr pub = rclcpp::create_publisher<Msg>(
m_node_interfaces.topics,
topic_name,
qos);
qos_profile);

this->store_publisher(pub, topic_name, performance_metrics::Tracker::Options());
}

template<typename Srv>
void PerformanceNodeBase::add_server(
const std::string & service_name,
const rmw_qos_profile_t & qos_profile)
const rclcpp::QoS & qos_profile)
{
std::function<void(
const std::shared_ptr<rmw_request_id_t> request_header,
Expand All @@ -152,7 +147,7 @@ void PerformanceNodeBase::add_server(
m_node_interfaces.services,
service_name,
callback_function,
qos_profile,
qos_profile.get_rmw_qos_profile(),
nullptr);

this->store_server(server, service_name, performance_metrics::Tracker::Options());
Expand All @@ -162,7 +157,7 @@ template<typename Srv>
void PerformanceNodeBase::add_periodic_client(
const std::string & service_name,
std::chrono::microseconds period,
const rmw_qos_profile_t & qos_profile,
const rclcpp::QoS & qos_profile,
size_t size)
{
this->add_client<Srv>(service_name, qos_profile);
Expand All @@ -182,14 +177,14 @@ void PerformanceNodeBase::add_periodic_client(
template<typename Srv>
void PerformanceNodeBase::add_client(
const std::string & service_name,
const rmw_qos_profile_t & qos_profile)
const rclcpp::QoS & qos_profile)
{
rclcpp::ClientBase::SharedPtr client = rclcpp::create_client<Srv>(
m_node_interfaces.base,
m_node_interfaces.graph,
m_node_interfaces.services,
service_name,
qos_profile,
qos_profile.get_rmw_qos_profile(),
nullptr);

this->store_client(client, service_name, performance_metrics::Tracker::Options());
Expand Down
16 changes: 7 additions & 9 deletions performance_test/test/test_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ TEST_F(TestSystem, SystemPubSubTest)
"my_topic",
std::chrono::milliseconds(10),
performance_test::msg_pass_by_t::PASS_BY_UNIQUE_PTR,
rmw_qos_profile_default);
rclcpp::SensorDataQoS());
ros2_system.add_node(pub_node);

auto sub_node =
Expand All @@ -66,7 +66,7 @@ TEST_F(TestSystem, SystemPubSubTest)
"my_topic",
performance_test::msg_pass_by_t::PASS_BY_SHARED_PTR,
performance_metrics::Tracker::Options(),
rmw_qos_profile_default);
rclcpp::SensorDataQoS());
ros2_system.add_node(sub_node);

ros2_system.spin(duration_sec);
Expand All @@ -90,14 +90,14 @@ TEST_F(TestSystem, SystemClientServerTest)
client_node->add_periodic_client<performance_test_msgs::srv::Sample>(
"my_service",
std::chrono::milliseconds(10),
rmw_qos_profile_default);
rclcpp::ServicesQoS());
ros2_system.add_node(client_node);

auto server_node =
std::make_shared<performance_test::PerformanceNode<rclcpp::Node>>("server_node");
server_node->add_server<performance_test_msgs::srv::Sample>(
"my_service",
rmw_qos_profile_default);
rclcpp::ServicesQoS());
ros2_system.add_node(server_node);

// discovery check does not work with client/server yet
Expand All @@ -115,13 +115,12 @@ TEST_F(TestSystem, SystemDifferentQoSTest)
auto duration_sec = std::chrono::seconds(1);
auto system_executor = performance_test::ExecutorType::STATIC_SINGLE_THREADED_EXECUTOR;
performance_test::System ros2_system(system_executor);
rmw_qos_profile_t qos_profile = rmw_qos_profile_default;
auto qos_profile = rclcpp::QoS(10);

// Create 1 pulisher node and 1 subscriber node
auto pub_node =
std::make_shared<performance_test::PerformanceNode<rclcpp::Node>>("pub_node");
qos_profile.reliability =
rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
qos_profile.reliability(rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT);
pub_node->add_periodic_publisher<performance_test_msgs::msg::Sample>(
"my_topic",
std::chrono::milliseconds(10),
Expand All @@ -131,8 +130,7 @@ TEST_F(TestSystem, SystemDifferentQoSTest)

auto sub_node =
std::make_shared<performance_test::PerformanceNode<rclcpp::Node>>("sub_node");
qos_profile.reliability =
rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_RELIABLE;
qos_profile.reliability(rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_RELIABLE);
sub_node->add_subscriber<performance_test_msgs::msg::Sample>(
"my_topic",
performance_test::msg_pass_by_t::PASS_BY_SHARED_PTR,
Expand Down
2 changes: 1 addition & 1 deletion performance_test_examples/src/client_nodes_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ int main(int argc, char ** argv)
options.n_services,
options.frequency,
options.msg_type,
rmw_qos_profile_default);
rclcpp::ServicesQoS());

ros2_system.add_nodes(client_nodes);

Expand Down
2 changes: 1 addition & 1 deletion performance_test_examples/src/publisher_nodes_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ int main(int argc, char ** argv)
options.msg_type,
performance_test::msg_pass_by_t::PASS_BY_UNIQUE_PTR,
options.msg_size,
rmw_qos_profile_default);
rclcpp::SensorDataQoS());

ros2_system.add_nodes(pub_nodes);

Expand Down
2 changes: 1 addition & 1 deletion performance_test_examples/src/server_nodes_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ int main(int argc, char ** argv)
options.n_clients,
options.n_clients + options.n_services,
options.msg_type,
rmw_qos_profile_default);
rclcpp::ServicesQoS());

ros2_system.add_nodes(server_nodes);

Expand Down
4 changes: 2 additions & 2 deletions performance_test_examples/src/simple_client_service_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ int main(int argc, char ** argv)
options.n_clients,
options.n_clients + options.n_services,
options.msg_type,
rmw_qos_profile_default);
rclcpp::ServicesQoS());

ros2_system.add_nodes(server_nodes);

Expand All @@ -80,7 +80,7 @@ int main(int argc, char ** argv)
options.n_services,
options.frequency,
options.msg_type,
rmw_qos_profile_default);
rclcpp::ServicesQoS());

ros2_system.add_nodes(client_nodes);

Expand Down
4 changes: 2 additions & 2 deletions performance_test_examples/src/simple_pub_sub_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ int main(int argc, char ** argv)
options.msg_type,
performance_test::msg_pass_by_t::PASS_BY_UNIQUE_PTR,
options.msg_size,
rmw_qos_profile_default);
rclcpp::SensorDataQoS());

ros2_system.add_nodes(pub_nodes);

Expand All @@ -83,7 +83,7 @@ int main(int argc, char ** argv)
options.msg_type,
performance_test::msg_pass_by_t::PASS_BY_SHARED_PTR,
performance_metrics::Tracker::Options(),
rmw_qos_profile_default);
rclcpp::SensorDataQoS());

ros2_system.add_nodes(sub_nodes);

Expand Down
2 changes: 1 addition & 1 deletion performance_test_examples/src/subscriber_nodes_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ int main(int argc, char ** argv)
options.msg_type,
performance_test::msg_pass_by_t::PASS_BY_SHARED_PTR,
performance_metrics::Tracker::Options(),
rmw_qos_profile_default);
rclcpp::SensorDataQoS());

ros2_system.add_nodes(sub_nodes);

Expand Down
2 changes: 1 addition & 1 deletion performance_test_factory/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ bool use_ipc = true;
auto sub_node = factory.create_node("sub_node_name", use_ipc);
std::string msg_type = "stamped10kb";
std::string topic_name = "my_topic";
factory.add_subscriber_from_strings(sub_node, msg_type, topic_name, rmw_qos_profile_default);
factory.add_subscriber_from_strings(sub_node, msg_type, topic_name, rclcpp::SensorDataQoS());
```

You can also create many similar nodes all at once.
Expand Down
Loading

0 comments on commit f04d164

Please sign in to comment.