Skip to content

Commit

Permalink
cleanups
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed Nov 14, 2024
1 parent 1ceae7a commit e1e0bae
Show file tree
Hide file tree
Showing 9 changed files with 8 additions and 56 deletions.
36 changes: 0 additions & 36 deletions rmw_zenoh_cpp/src/detail/liveliness_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -453,42 +453,6 @@ Entity::Entity(

///=============================================================================
std::shared_ptr<Entity> Entity::make(
z_id_t zid,
const std::string & nid,
const std::string & id,
EntityType type,
NodeInfo node_info,
std::optional<TopicInfo> topic_info)
{
if (id.empty()) {
RCUTILS_SET_ERROR_MSG("Invalid id.");
return nullptr;
}
if (entity_to_str.find(type) == entity_to_str.end()) {
RCUTILS_SET_ERROR_MSG("Invalid entity type.");
return nullptr;
}
if (node_info.ns_.empty() || node_info.name_.empty()) {
RCUTILS_SET_ERROR_MSG("Invalid node_info for entity.");
return nullptr;
}
if (type != EntityType::Node && !topic_info.has_value()) {
RCUTILS_SET_ERROR_MSG("Invalid topic_info for entity.");
return nullptr;
}

return std::make_shared<Entity>(
Entity{
zid_to_str(zid),
nid,
id,
std::move(type),
std::move(node_info),
std::move(topic_info)});
}

///=============================================================================
std::shared_ptr<Entity> Entity::make_cpp(
zenoh::Id zid,
const std::string & nid,
const std::string & id,
Expand Down
8 changes: 0 additions & 8 deletions rmw_zenoh_cpp/src/detail/liveliness_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,14 +128,6 @@ class Entity
/// @param topic_info An optional topic information for relevant entities.
/// @return An entity if all inputs are valid. This way no invalid entities can be created.
static EntityPtr make(
z_id_t zid,
const std::string & nid,
const std::string & id,
EntityType type,
NodeInfo node_info,
std::optional<TopicInfo> topic_info = std::nullopt);

static EntityPtr make_cpp(
zenoh::Id zid,
const std::string & nid,
const std::string & id,
Expand Down
7 changes: 2 additions & 5 deletions rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,6 @@ void rmw_context_impl_s::graph_sub_data_handler(z_loaned_sample_t * sample, void
rmw_context_impl_s::Data::Data(
std::size_t domain_id,
const std::string & enclave,
z_owned_session_t session,
std::shared_ptr<zenoh::Session> session_cpp,
const std::string & liveliness_str,
std::shared_ptr<rmw_zenoh_cpp::GraphCache> graph_cache
Expand All @@ -94,7 +93,6 @@ rmw_context_impl_s::Data::Data(
)
: enclave_(std::move(enclave)),
domain_id_(std::move(domain_id)),
session_(std::move(session)),
session_cpp_(session_cpp),
liveliness_str_(std::move(liveliness_str)),
graph_cache_(std::move(graph_cache)),
Expand Down Expand Up @@ -187,7 +185,7 @@ rmw_ret_t rmw_context_impl_s::Data::subscribe_to_ros_graph()
z_undeclare_subscriber(z_move(this->graph_subscriber_));
});
if (zc_liveliness_declare_subscriber(
z_loan(session_),
z_loan(session_cpp_->_0),
&graph_subscriber_, z_loan(keyexpr),
z_move(callback), &sub_options) != Z_OK)
{
Expand Down Expand Up @@ -366,7 +364,6 @@ rmw_context_impl_s::rmw_context_impl_s(
data_ = std::make_shared<Data>(
domain_id,
std::move(enclave),
std::move(session->_0),
std::move(session),
std::move(liveliness_str),
std::move(graph_cache)
Expand Down Expand Up @@ -397,7 +394,7 @@ std::string rmw_context_impl_s::enclave() const
const z_loaned_session_t * rmw_context_impl_s::session() const
{
std::lock_guard<std::recursive_mutex> lock(data_->mutex_);
return z_loan(data_->session_);
return z_loan(data_->session_cpp_->_0);
}

const std::shared_ptr<zenoh::Session> rmw_context_impl_s::session_cpp() const
Expand Down
3 changes: 1 addition & 2 deletions rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,6 @@ class rmw_context_impl_s final
Data(
std::size_t domain_id,
const std::string & enclave,
z_owned_session_t session,
std::shared_ptr<zenoh::Session> session_cpp,
const std::string & liveliness_str,
std::shared_ptr<rmw_zenoh_cpp::GraphCache> graph_cache
Expand All @@ -133,7 +132,7 @@ class rmw_context_impl_s final
// The ROS domain id of this context.
std::size_t domain_id_;
// An owned session.
z_owned_session_t session_;
// z_owned_session_t session_;
std::shared_ptr<zenoh::Session> session_cpp_;
// Liveliness keyexpr string to subscribe to for ROS graph changes.
std::string liveliness_str_;
Expand Down
2 changes: 1 addition & 1 deletion rmw_zenoh_cpp/src/detail/rmw_node_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ std::shared_ptr<NodeData> NodeData::make(
const std::string & enclave)
{
// Create the entity.
auto entity = rmw_zenoh_cpp::liveliness::Entity::make_cpp(
auto entity = rmw_zenoh_cpp::liveliness::Entity::make(
session->get_zid(),
std::to_string(id),
std::to_string(id),
Expand Down
2 changes: 1 addition & 1 deletion rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ std::shared_ptr<PublisherData> PublisherData::make(
});

std::size_t domain_id = node_info.domain_id_;
auto entity = liveliness::Entity::make_cpp(
auto entity = liveliness::Entity::make(
session->get_zid(),
std::to_string(node_id),
std::to_string(publisher_id),
Expand Down
2 changes: 1 addition & 1 deletion rmw_zenoh_cpp/src/detail/rmw_service_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ std::shared_ptr<ServiceData> ServiceData::make(
});

std::size_t domain_id = node_info.domain_id_;
auto entity = liveliness::Entity::make_cpp(
auto entity = liveliness::Entity::make(
session->get_zid(),
std::to_string(node_id),
std::to_string(service_id),
Expand Down
2 changes: 1 addition & 1 deletion rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ std::shared_ptr<SubscriptionData> SubscriptionData::make(
// Everything above succeeded and is setup properly. Now declare a subscriber
// with Zenoh; after this, callbacks may come in at any time.
std::size_t domain_id = node_info.domain_id_;
auto entity = liveliness::Entity::make_cpp(
auto entity = liveliness::Entity::make(
session->get_zid(),
std::to_string(node_id),
std::to_string(subscription_id),
Expand Down
2 changes: 1 addition & 1 deletion rmw_zenoh_cpp/src/rmw_zenoh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1568,7 +1568,7 @@ rmw_create_client(
node_data,
"NodeData not found.",
return nullptr);
client_data->entity = rmw_zenoh_cpp::liveliness::Entity::make_cpp(
client_data->entity = rmw_zenoh_cpp::liveliness::Entity::make(
session->get_zid(),
std::to_string(node_data->id()),
std::to_string(
Expand Down

0 comments on commit e1e0bae

Please sign in to comment.