Skip to content

Commit

Permalink
Replace hash_gid with FNV-1a
Browse files Browse the repository at this point in the history
  • Loading branch information
fuzzypixelz committed Jan 15, 2025
1 parent f040f5c commit fdb5633
Show file tree
Hide file tree
Showing 5 changed files with 29 additions and 19 deletions.
13 changes: 1 addition & 12 deletions rmw_zenoh_cpp/src/detail/liveliness_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -442,7 +442,7 @@ Entity::Entity(
sizeof(keyexpr_gid.high64));

// We also hash the liveliness keyexpression into a size_t that we use to index into our maps.
this->keyexpr_hash_ = hash_gid(this->gid_);
this->keyexpr_hash_ = std::hash<Gid>{}(this->gid_);
}

///=============================================================================
Expand Down Expand Up @@ -670,15 +670,4 @@ std::string demangle_name(const std::string & input)
return output;
}
} // namespace liveliness

///=============================================================================
size_t hash_gid(const std::array<uint8_t, RMW_GID_STORAGE_SIZE> gid)
{
std::stringstream hash_str;
hash_str << std::hex;
for (const auto & g : gid) {
hash_str << static_cast<int>(g);
}
return std::hash<std::string>{}(hash_str.str());
}
} // namespace rmw_zenoh_cpp
25 changes: 23 additions & 2 deletions rmw_zenoh_cpp/src/detail/liveliness_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -234,8 +234,7 @@ std::string qos_to_keyexpr(const rmw_qos_profile_t & qos);
std::optional<rmw_qos_profile_t> keyexpr_to_qos(const std::string & keyexpr);
} // namespace liveliness

///=============================================================================
size_t hash_gid(const std::array<uint8_t, RMW_GID_STORAGE_SIZE> gid);
using Gid = std::array<uint8_t, RMW_GID_STORAGE_SIZE>;
} // namespace rmw_zenoh_cpp

///=============================================================================
Expand Down Expand Up @@ -270,6 +269,28 @@ struct equal_to<rmw_zenoh_cpp::liveliness::ConstEntityPtr>
return lhs->keyexpr_hash() == rhs->keyexpr_hash();
}
};

template<>
struct hash<rmw_zenoh_cpp::Gid>
{
std::size_t operator()(const rmw_zenoh_cpp::Gid & gid) const noexcept
{
// This function implemented FNV-1a 64-bit as the GID is small enough (e.g. as of commit db4d05e
// of ros2/rmw RMW_GID_STORAGE_SIZE is set to 16) and FNV is known to be efficient in such cases.
//
// See https://github.com/ros2/rmw/blob/db4d05e/rmw/include/rmw/types.h#L44
// and https://datatracker.ietf.org/doc/html/draft-eastlake-fnv-17.html
static constexpr uint64_t FNV_OFFSET_BASIS_64 = 0x00000100000001b3;
static constexpr uint64_t FNV_PRIME_64 = 0xcbf29ce484222325;

uint64_t hash = FNV_OFFSET_BASIS_64;
for (const uint8_t & byte : gid) {
hash ^= byte;
hash *= FNV_PRIME_64;
}
return hash;
}
};
} // namespace std

#endif // DETAIL__LIVELINESS_UTILS_HPP_
4 changes: 2 additions & 2 deletions rmw_zenoh_cpp/src/detail/rmw_service_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -346,7 +346,7 @@ rmw_ret_t ServiceData::take_request(
request_header->received_timestamp = query->get_received_timestamp();

// Add this query to the map, so that rmw_send_response can quickly look it up later.
const size_t hash = rmw_zenoh_cpp::hash_gid(writer_guid);
const size_t hash = std::hash<Gid>{}(writer_guid);
std::unordered_map<size_t, SequenceToQuery>::iterator it = sequence_to_query_map_.find(hash);
if (it == sequence_to_query_map_.end()) {
SequenceToQuery stq;
Expand Down Expand Up @@ -384,7 +384,7 @@ rmw_ret_t ServiceData::send_response(
memcpy(writer_guid.data(), request_id->writer_guid, RMW_GID_STORAGE_SIZE);

// Create the queryable payload
const size_t hash = hash_gid(writer_guid);
const size_t hash = std::hash<Gid>{}(writer_guid);
std::unordered_map<size_t, SequenceToQuery>::iterator it = sequence_to_query_map_.find(hash);
if (it == sequence_to_query_map_.end()) {
// If there is no data associated with this request, the higher layers of
Expand Down
4 changes: 2 additions & 2 deletions rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -615,7 +615,7 @@ void SubscriptionData::add_new_message(
}

// Check for messages lost if the new sequence number is not monotonically increasing.
const size_t gid_hash = hash_gid(msg->attachment.copy_gid());
const size_t gid_hash = std::hash<Gid>{}(msg->attachment.copy_gid());
auto last_known_pub_it = last_known_published_msg_.find(gid_hash);
if (last_known_pub_it != last_known_published_msg_.end()) {
const int64_t seq_increment = std::abs(
Expand All @@ -629,7 +629,7 @@ void SubscriptionData::add_new_message(
}
}
// Always update the last known sequence number for the publisher.
last_known_published_msg_[gid_hash] = msg->attachment.sequence_number();
last_known_published_msg_[gid] = msg->attachment.sequence_number();

message_queue_.emplace_back(std::move(msg));

Expand Down
2 changes: 1 addition & 1 deletion rmw_zenoh_cpp/src/detail/rmw_subscription_data.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ class SubscriptionData final : public std::enable_shared_from_this<SubscriptionD
std::unique_ptr<MessageTypeSupport> type_support_;
std::deque<std::unique_ptr<Message>> message_queue_;
// Map GID of a subscription to the sequence number of the message it published.
std::unordered_map<size_t, int64_t> last_known_published_msg_;
std::unordered_map<Gid, int64_t> last_known_published_msg_;
// Wait set data.
rmw_wait_set_data_t * wait_set_data_;
// Callback managers.
Expand Down

0 comments on commit fdb5633

Please sign in to comment.