Skip to content

Commit

Permalink
Merge branch 'rolling' into yadu/bump_zenoh_with_tokio
Browse files Browse the repository at this point in the history
  • Loading branch information
Yadunund committed Apr 13, 2024
2 parents 59ffcdd + c1c6f95 commit 615dcbf
Show file tree
Hide file tree
Showing 11 changed files with 267 additions and 112 deletions.
1 change: 1 addition & 0 deletions rmw_zenoh_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ find_package(zenohc REQUIRED)

add_library(rmw_zenoh_cpp SHARED
src/detail/attachment_helpers.cpp
src/detail/cdr.cpp
src/detail/event.cpp
src/detail/identifier.cpp
src/detail/graph_cache.cpp
Expand Down
42 changes: 42 additions & 0 deletions rmw_zenoh_cpp/src/detail/cdr.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "fastcdr/Cdr.h"
#include "fastcdr/FastBuffer.h"
#include "fastcdr/config.h"

#include "cdr.hpp"

rmw_zenoh_cpp::Cdr::Cdr(eprosima::fastcdr::FastBuffer & fastbuffer)
#if FASTCDR_VERSION_MAJOR == 1
: cdr_(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR)
#else
: cdr_(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::CdrVersion::DDS_CDR)
#endif
{
}

size_t rmw_zenoh_cpp::Cdr::get_serialized_data_length() const
{
#if FASTCDR_VERSION_MAJOR == 1
return cdr_.getSerializedDataLength();
#else
return cdr_.get_serialized_data_length();
#endif
}

eprosima::fastcdr::Cdr & rmw_zenoh_cpp::Cdr::get_cdr()
{
return cdr_;
}
39 changes: 39 additions & 0 deletions rmw_zenoh_cpp/src/detail/cdr.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DETAIL__CDR_HPP_
#define DETAIL__CDR_HPP_

#include "fastcdr/Cdr.h"
#include "fastcdr/FastBuffer.h"

// A wrapper class to paper over the differences between Fast-CDR v1 and Fast-CDR v2
namespace rmw_zenoh_cpp
{
class Cdr final
{
public:
explicit Cdr(eprosima::fastcdr::FastBuffer & fastbuffer);

eprosima::fastcdr::Cdr & get_cdr();

size_t get_serialized_data_length() const;

private:
eprosima::fastcdr::Cdr cdr_;
};

} // namespace rmw_zenoh_cpp

#endif // DETAIL__CDR_HPP_
10 changes: 7 additions & 3 deletions rmw_zenoh_cpp/src/detail/event.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -184,6 +184,7 @@ void EventsManager::add_new_event(
///=============================================================================
void EventsManager::attach_event_condition(
rmw_zenoh_event_type_t event_id,
std::mutex * condition_mutex,
std::condition_variable * condition_variable)
{
if (event_id > ZENOH_EVENT_ID_MAX) {
Expand All @@ -194,7 +195,8 @@ void EventsManager::attach_event_condition(
return;
}

std::lock_guard<std::mutex> lock(event_condition_mutex_);
std::lock_guard<std::mutex> lock(update_event_condition_mutex_);
event_condition_mutexes_[event_id] = condition_mutex;
event_conditions_[event_id] = condition_variable;
}

Expand All @@ -209,7 +211,8 @@ void EventsManager::detach_event_condition(rmw_zenoh_event_type_t event_id)
return;
}

std::lock_guard<std::mutex> lock(event_condition_mutex_);
std::lock_guard<std::mutex> lock(update_event_condition_mutex_);
event_condition_mutexes_[event_id] = nullptr;
event_conditions_[event_id] = nullptr;
}

Expand All @@ -224,8 +227,9 @@ void EventsManager::notify_event(rmw_zenoh_event_type_t event_id)
return;
}

std::lock_guard<std::mutex> lock(event_condition_mutex_);
std::lock_guard<std::mutex> lock(update_event_condition_mutex_);
if (event_conditions_[event_id] != nullptr) {
std::lock_guard<std::mutex> cvlk(*event_condition_mutexes_[event_id]);
event_conditions_[event_id]->notify_one();
}
}
4 changes: 3 additions & 1 deletion rmw_zenoh_cpp/src/detail/event.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,7 @@ class EventsManager
/// @param condition_variable to attach.
void attach_event_condition(
rmw_zenoh_event_type_t event_id,
std::mutex * condition_mutex,
std::condition_variable * condition_variable);

/// @brief Detach the condition variable provided by rmw_wait.
Expand All @@ -154,7 +155,8 @@ class EventsManager
/// Mutex to lock when read/writing members.
mutable std::mutex event_mutex_;
/// Mutex to lock for event_condition.
mutable std::mutex event_condition_mutex_;
mutable std::mutex update_event_condition_mutex_;
std::mutex * event_condition_mutexes_[ZENOH_EVENT_ID_MAX + 1]{nullptr};
/// Condition variable to attach for event notifications.
std::condition_variable * event_conditions_[ZENOH_EVENT_ID_MAX + 1]{nullptr};
/// User callback that can be set via data_callback_mgr.set_callback().
Expand Down
7 changes: 6 additions & 1 deletion rmw_zenoh_cpp/src/detail/guard_condition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,21 +33,26 @@ void GuardCondition::trigger()
has_triggered_ = true;

if (condition_variable_ != nullptr) {
std::lock_guard<std::mutex> cvlk(*condition_mutex_);
condition_variable_->notify_one();
}
}

///==============================================================================
void GuardCondition::attach_condition(std::condition_variable * condition_variable)
void GuardCondition::attach_condition(
std::mutex * condition_mutex,
std::condition_variable * condition_variable)
{
std::lock_guard<std::mutex> lock(internal_mutex_);
condition_mutex_ = condition_mutex;
condition_variable_ = condition_variable;
}

///==============================================================================
void GuardCondition::detach_condition()
{
std::lock_guard<std::mutex> lock(internal_mutex_);
condition_mutex_ = nullptr;
condition_variable_ = nullptr;
}

Expand Down
5 changes: 3 additions & 2 deletions rmw_zenoh_cpp/src/detail/guard_condition.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class GuardCondition final
// Sets has_triggered_ to true and calls notify_one() on condition_variable_ if set.
void trigger();

void attach_condition(std::condition_variable * condition_variable);
void attach_condition(std::mutex * condition_mutex, std::condition_variable * condition_variable);

void detach_condition();

Expand All @@ -38,7 +38,8 @@ class GuardCondition final
private:
mutable std::mutex internal_mutex_;
std::atomic_bool has_triggered_;
std::condition_variable * condition_variable_;
std::mutex * condition_mutex_{nullptr};
std::condition_variable * condition_variable_{nullptr};
};

#endif // DETAIL__GUARD_CONDITION_HPP_
4 changes: 2 additions & 2 deletions rmw_zenoh_cpp/src/detail/liveliness_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -319,8 +319,8 @@ std::shared_ptr<Entity> Entity::make(
return std::make_shared<Entity>(
Entity{
zid_to_str(zid),
std::move(nid),
std::move(id),
nid,
id,
std::move(type),
std::move(node_info),
std::move(topic_info)});
Expand Down
Loading

0 comments on commit 615dcbf

Please sign in to comment.