Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Verify a zenoh router is available for the session #61

Merged
merged 3 commits into from
Nov 17, 2023
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions rmw_zenoh_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ add_library(rmw_zenoh_cpp SHARED
src/detail/type_support.cpp
src/detail/type_support_common.cpp
src/detail/zenoh_config.cpp
src/detail/zenoh_router_check.cpp
src/rmw_event.cpp
src/rmw_get_network_flow_endpoints.cpp
src/rmw_get_node_info_and_types.cpp
Expand Down
88 changes: 88 additions & 0 deletions rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
// Copyright 2023 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 "zenoh_router_check.hpp"

#include <rcutils/env.h>
#include <rcutils/logging_macros.h>

#include <string>
#include <sstream>
#include <iomanip>
clalancette marked this conversation as resolved.
Show resolved Hide resolved

namespace
{

// Convert a Zenoh Id to a string
// Zenoh IDs are LSB-first 128bit unsigned and non-zero integers in hexadecimal lowercase.
// @param pid Zenoh Id to convert
std::string ZidToStr(z_id_t pid)
clalancette marked this conversation as resolved.
Show resolved Hide resolved
{
std::stringstream ss;
int len = 0;
for (int i = 0; i < 16; i++) {
clalancette marked this conversation as resolved.
Show resolved Hide resolved
if (pid.id[i]) {
len = i + 1;
}
}
if (!len) {
ss << "";
} else {
for (int i = len - 1; i >= 0; --i) {
ss << std::hex << std::setfill('0') << std::setw(2) << static_cast<int>(pid.id[i]);
}
}
return ss.str();
}

} // namespace

rmw_ret_t zenoh_router_check(z_session_t session)
{
// Initialize context for callback
void * context = malloc(sizeof(int));
*(static_cast<int *>(context)) = 0;
clalancette marked this conversation as resolved.
Show resolved Hide resolved

// Define callback
auto callback = [](const struct z_id_t * id, void * ctx) {
const std::string id_str = ZidToStr(*id);
RCUTILS_LOG_INFO_NAMED(
"ZenouRouterCheck",
"A Zenoh router connected to the session with id '%s'", id_str.c_str());
// Note: Callback is guaranteed to never be called
// concurrently according to z_info_routers_zid docstring
(*(static_cast<int *>(ctx)))++;
};

z_owned_closure_zid_t router_callback = z_closure(callback, nullptr /* drop */, context);
z_info_routers_zid(session, z_move(router_callback));

rmw_ret_t ret;
if (*(static_cast<int *>(context)) == 0) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm trying to understand how the z_info_routers_zid() API works.

/**
 * Fetches the Zenoh IDs of all connected routers.
 *
 * `callback` will be called once for each ID, is guaranteed to never be called concurrently,
 * and is guaranteed to be dropped before this function exits.
 *
 * Retuns 0 on success, negative values on failure.
 */
ZENOHC_API
int8_t z_info_routers_zid(struct z_session_t session,
                          struct z_owned_closure_zid_t *callback);

If it returns an int8_t, is it a blocking function or will the function execute callbacks asynchronously? If its the former, we could just check if the return value is 0 and if so return RMW_RET_OK? Unless we plan to parse the zids we receive in the callbacks to check if the zid matches that of the zenoh router we run (and not any other zenoh router)?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is it a blocking function or will the function execute callbacks asynchronously?

It is a blocking function.

we could just check if the return value is 0 and if so return RMW_RET_OK?

It "returns 0 in success" but that doesn't convey whether there are or not available routers. It would return 0 even if the zenoh router is missing. This only states whether the execution was correct. (Just realized that we should return error in case there is a failure, adding that...)

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Unless we plan to parse the zids we receive in the callbacks to check if the zid matches that of the zenoh router we run (and not any other zenoh router)?

For the moment we need the callback to check that at least a router is connected to the session. I added the parsing of the id mainly for logging purposes. We could at some point verify the id to correctly assert that we are connected to the zenoh router we want. However it is a bit early for this I think, for the moment we don't have environments with more than one zenoh router.

RCUTILS_LOG_ERROR_NAMED(
"ZenouRouterCheck",
clalancette marked this conversation as resolved.
Show resolved Hide resolved
"No Zenoh router connected to the session");
ret = RMW_RET_ERROR;
} else {
RCUTILS_LOG_INFO_NAMED(
"ZenouRouterCheck",
"There are %d Zenoh routers connected to the session", *(static_cast<int *>(context)));

ret = RMW_RET_OK;
}

// Not using the drop function from the closure as we want to keep the context for logging.
free(context);
return ret;
}
27 changes: 27 additions & 0 deletions rmw_zenoh_cpp/src/detail/zenoh_router_check.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
// Copyright 2023 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__ZENOH_ROUTER_CHECK_HPP_
#define DETAIL__ZENOH_ROUTER_CHECK_HPP_

#include <zenoh.h>

#include "rmw/ret_types.h"

/// Check if a Zenoh router is connected to the session.
/// @param session Zenoh session to check.
/// @return RMW_RET_OK if a Zenoh router is connected to the session.
rmw_ret_t zenoh_router_check(z_session_t session);
clalancette marked this conversation as resolved.
Show resolved Hide resolved

#endif // DETAIL__ZENOH_ROUTER_CHECK_HPP_
7 changes: 7 additions & 0 deletions rmw_zenoh_cpp/src/rmw_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "detail/identifier.hpp"
#include "detail/rmw_data_types.hpp"
#include "detail/zenoh_config.hpp"
#include "detail/zenoh_router_check.hpp"

#include "rcutils/env.h"
#include "rcutils/logging_macros.h"
Expand Down Expand Up @@ -173,6 +174,12 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
z_close(z_move(context->impl->session));
});

// Verify if the zenoh router is running.
if ((ret = zenoh_router_check(z_loan(context->impl->session))) != RMW_RET_OK) {
RMW_SET_ERROR_MSG("Error while checking for Zenoh router");
return ret;
}

// Initialize the shm manager if shared_memory is enabled in the config.
if (shm_enabled._cstr != nullptr &&
strcmp(shm_enabled._cstr, "true") == 0)
Expand Down
Loading