Skip to content

Commit

Permalink
Reduce diff
Browse files Browse the repository at this point in the history
  • Loading branch information
roncapat committed Oct 7, 2023
1 parent c4f3ab3 commit f36cd2a
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 24 deletions.
4 changes: 1 addition & 3 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,9 +84,7 @@ rclcpp::QoS publisher_qos_for_topic(
YAML::decode_for_version<std::vector<rosbag2_transport::Rosbag2QoS>>(
profiles_yaml,
topic.version);
return rosbag2_transport::Rosbag2QoS::adapt_offer_to_recorded_offers(
topic.name,
offered_qos_profiles);
return Rosbag2QoS::adapt_offer_to_recorded_offers(topic.name, offered_qos_profiles);
}
} // namespace

Expand Down
38 changes: 18 additions & 20 deletions rosbag2_transport/src/rosbag2_transport/qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ static const rmw_time_t RMW_FASTRTPS_FOXY_INFINITE {0x7FFFFFFFll, 0xFFFFFFFFll};
static const rmw_time_t RMW_CONNEXT_FOXY_INFINITE {0x7FFFFFFFll, 0x7FFFFFFFll};
} // namespace


namespace YAML
{

Expand Down Expand Up @@ -132,6 +131,23 @@ bool convert<rmw_time_t>::decode(const Node & node, rmw_time_t & time)
return true;
}

Node convert<rosbag2_transport::Rosbag2QoS>::encode(
const rosbag2_transport::Rosbag2QoS & qos)
{
const auto & p = qos.get_rmw_qos_profile();
Node node;
node["history"] = convert<rmw_qos_history_policy_t>::encode(p.history);
node["depth"] = p.depth;
node["reliability"] = convert<rmw_qos_reliability_policy_t>::encode(p.reliability);
node["durability"] = convert<rmw_qos_durability_policy_t>::encode(p.durability);
node["deadline"] = p.deadline;
node["lifespan"] = p.lifespan;
node["liveliness"] = convert<rmw_qos_liveliness_policy_t>::encode(p.liveliness);
node["liveliness_lease_duration"] = p.liveliness_lease_duration;
node["avoid_ros_namespace_conventions"] = p.avoid_ros_namespace_conventions;
return node;
}

bool convert<rosbag2_transport::Rosbag2QoS>::decode(
const Node & node, rosbag2_transport::Rosbag2QoS & qos, int version)
{
Expand Down Expand Up @@ -161,23 +177,6 @@ bool convert<rosbag2_transport::Rosbag2QoS>::decode(
.avoid_ros_namespace_conventions(node["avoid_ros_namespace_conventions"].as<bool>());
return true;
}

Node convert<rosbag2_transport::Rosbag2QoS>::encode(
const rosbag2_transport::Rosbag2QoS & qos)
{
const auto & p = qos.get_rmw_qos_profile();
Node node;
node["history"] = convert<rmw_qos_history_policy_t>::encode(p.history);
node["depth"] = p.depth;
node["reliability"] = convert<rmw_qos_reliability_policy_t>::encode(p.reliability);
node["durability"] = convert<rmw_qos_durability_policy_t>::encode(p.durability);
node["deadline"] = p.deadline;
node["lifespan"] = p.lifespan;
node["liveliness"] = convert<rmw_qos_liveliness_policy_t>::encode(p.liveliness);
node["liveliness_lease_duration"] = p.liveliness_lease_duration;
node["avoid_ros_namespace_conventions"] = p.avoid_ros_namespace_conventions;
return node;
}
} // namespace YAML

namespace rosbag2_transport
Expand Down Expand Up @@ -262,8 +261,7 @@ bool operator==(const rmw_time_t & lhs, const rmw_time_t & rhs)
* policies that affect compatibility.
* This means it excludes history and lifespan from the equality check.
*/
template<typename T>
bool all_profiles_effectively_same(const std::vector<T> & profiles)
bool all_profiles_effectively_same(const std::vector<Rosbag2QoS> & profiles)
{
auto iterator = profiles.begin();
const auto p_ref = iterator->get_rmw_qos_profile();
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_transport/src/rosbag2_transport/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -508,7 +508,7 @@ std::string RecorderImpl::serialized_offered_qos_profiles_for_topic(
{
YAML::Node offered_qos_profiles;
for (const auto & info : topics_endpoint_info) {
offered_qos_profiles.push_back(rosbag2_transport::Rosbag2QoS(info.qos_profile()));
offered_qos_profiles.push_back(Rosbag2QoS(info.qos_profile()));
}
return YAML::Dump(offered_qos_profiles);
}
Expand Down

0 comments on commit f36cd2a

Please sign in to comment.