Skip to content

Commit

Permalink
Fix tests, move f-n, return early
Browse files Browse the repository at this point in the history
Signed-off-by: Anas Abou Allaban <[email protected]>
  • Loading branch information
piraka9011 committed Apr 10, 2020
1 parent 5d53bb6 commit 4b6ec66
Show file tree
Hide file tree
Showing 3 changed files with 36 additions and 34 deletions.
40 changes: 27 additions & 13 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <memory>
#include <queue>
#include <string>
#include <vector>
#include <unordered_map>
#include <utility>

#include "rcl/graph.h"
Expand All @@ -36,6 +36,31 @@
#include "rosbag2_node.hpp"
#include "replayable_message.hpp"

namespace
{
/**
* Determine which QoS to offer for a topic.
* The priority of the profile selected is:
* 1. The override specified in play_options (if one exists for the topic).
* 2. The default RMW QoS profile.
*
* \param topic_name The full name of the topic, with namespace (ex. /arm/joint_status).
* \param topic_qos_profile_overrides A map of topic to QoS profile overrides.
* @return The QoS profile to be used for subscribing.
*/
rclcpp::QoS publisher_qos_for_topic(
const std::string & topic_name,
std::unordered_map<std::string, rclcpp::QoS> topic_qos_profile_overrides)
{
auto qos_it = topic_qos_profile_overrides.find(topic_name);
if (qos_it != topic_qos_profile_overrides.end()) {
ROSBAG2_TRANSPORT_LOG_INFO_STREAM("Overriding QoS profile for topic " << topic_name);
return rosbag2_transport::Rosbag2QoS{qos_it->second};
}
return rosbag2_transport::Rosbag2QoS{};
}
} // namespace

namespace rosbag2_transport
{

Expand Down Expand Up @@ -154,22 +179,11 @@ void Player::play_messages_until_queue_empty(const PlayOptions & options)
}
}

rclcpp::QoS Player::publisher_qos_for_topic(const std::string & topic_name)
{
auto qos_it = topic_qos_profile_overrides_.find(topic_name);
if (qos_it != topic_qos_profile_overrides_.end()) {
ROSBAG2_TRANSPORT_LOG_INFO_STREAM("Overriding QoS profile for topic " << topic_name);
return Rosbag2QoS{qos_it->second};
} else {
return Rosbag2QoS{};
}
}

void Player::prepare_publishers()
{
auto topics = reader_->get_all_topics_and_types();
for (const auto & topic : topics) {
auto topic_qos = publisher_qos_for_topic(topic.name);
auto topic_qos = publisher_qos_for_topic(topic.name, topic_qos_profile_overrides_);
publishers_.insert(
std::make_pair(
topic.name, rosbag2_transport_->create_generic_publisher(
Expand Down
12 changes: 0 additions & 12 deletions rosbag2_transport/src/rosbag2_transport/player.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,18 +60,6 @@ class Player
void play_messages_from_queue(const PlayOptions & options);
void play_messages_until_queue_empty(const PlayOptions & options);
void prepare_publishers();

/**
* Determine which QoS to offer for a topic.
* The priority of the profile selected is:
* 1. The override specified in play_options (if one exists for the topic).
* 2. The default RMW QoS profile.
*
* \param topic_name The full name of the topic, with namespace (ex. /arm/joint_status).
* @return The QoS profile to be used for subscribing.
*/
rclcpp::QoS publisher_qos_for_topic(const std::string & topic_name);

static constexpr double read_ahead_lower_bound_percentage_ = 0.9;
static const std::chrono::milliseconds queue_read_wait_period_;

Expand Down
18 changes: 9 additions & 9 deletions rosbag2_transport/test/rosbag2_transport/test_play.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,15 +150,15 @@ class RosBag2PlayQosOverrideTestFixture : public RosBag2PlayTestFixture

TEST_F(RosBag2PlayQosOverrideTestFixture, topic_qos_profiles_overriden)
{
const auto qos_request = rclcpp::QoS{rclcpp::KeepAll()}.durability_volatile();
const auto qos_request = rclcpp::QoS{rclcpp::KeepAll()}.best_effort();
sub_->add_subscription<test_msgs::msg::BasicTypes>(topic_name_, num_msgs_, qos_request);
auto await_received_messages = sub_->spin_subscriptions();

// The previous subscriber requested durability VOLATILE which is the default in rosbag2.
// We override the requested durability to TRANSIENT_LOCAL so that we can receive messages.
// If the previous subscription requested TRANSIENT_LOCAL and we overrode with VOLATILE, then we
// The previous subscriber requested reliability BEST_EFFORT.
// We override the requested reliability to RELIABLE so that we can receive messages.
// If the previous subscription requested BEST_EFFORT and we overrode with RELIABLE, then we
// would not receive any messages.
const auto qos_override = rclcpp::QoS{rclcpp::KeepAll()}.transient_local();
const auto qos_override = rclcpp::QoS{rclcpp::KeepAll()}.reliable();
const auto topic_qos_profile_overrides = std::unordered_map<std::string, rclcpp::QoS>{
std::pair<std::string, rclcpp::QoS>{topic_name_, qos_override},
};
Expand All @@ -180,14 +180,14 @@ TEST_F(RosBag2PlayQosOverrideTestFixture, topic_qos_profiles_overriden)

TEST_F(RosBag2PlayQosOverrideTestFixture, topic_qos_profiles_overriden_incompatible)
{
const auto qos_request = rclcpp::QoS{rclcpp::KeepAll()}.transient_local();
const auto qos_request = rclcpp::QoS{rclcpp::KeepAll()}.reliable();
sub_->add_subscription<test_msgs::msg::BasicTypes>(topic_name_, num_msgs_, qos_request);
auto await_received_messages = sub_->spin_subscriptions();

// The previous subscriber requested durability TRANSIENT_LOCAL.
// We override the requested durability to VOLATILE.
// The previous subscriber requested reliability RELIABLE.
// We override the requested reliability to BEST_EFFORT.
// Since they are incompatible policies, we will not receive any messages.
const auto qos_override = rclcpp::QoS{rclcpp::KeepAll()}.durability_volatile();
const auto qos_override = rclcpp::QoS{rclcpp::KeepAll()}.best_effort();
const auto topic_qos_profile_overrides = std::unordered_map<std::string, rclcpp::QoS>{
std::pair<std::string, rclcpp::QoS>{topic_name_, qos_override},
};
Expand Down

0 comments on commit 4b6ec66

Please sign in to comment.