Skip to content

Commit

Permalink
make linters happy
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 22, 2024
1 parent e71614a commit da108bf
Show file tree
Hide file tree
Showing 10 changed files with 117 additions and 135 deletions.
12 changes: 4 additions & 8 deletions rmw_zenoh_cpp/src/detail/attachment_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,7 @@ AttachmentData::AttachmentData(
{
sequence_number = _sequence_number;
source_timestamp = _source_timestamp;
for (size_t i = 0; i < RMW_GID_STORAGE_SIZE; ++i)
{
for (size_t i = 0; i < RMW_GID_STORAGE_SIZE; ++i) {
source_gid.push_back(_source_gid[RMW_GID_STORAGE_SIZE - 1 - i]);
}
}
Expand Down Expand Up @@ -63,22 +62,19 @@ AttachmentData::AttachmentData(const zenoh::Bytes & attachment)
{
zenoh::ext::Deserializer deserializer(std::move(attachment));
const auto sequence_number_str = deserializer.deserialize<std::string>();
if (sequence_number_str != "sequence_number")
{
if (sequence_number_str != "sequence_number") {
throw std::runtime_error("sequence_number is not found in the attachment.");
}
this->sequence_number = deserializer.deserialize<int64_t>();

const auto source_timestamp_str = deserializer.deserialize<std::string>();
if (source_timestamp_str != "source_timestamp")
{
if (source_timestamp_str != "source_timestamp") {
throw std::runtime_error("source_timestamp is not found in the attachment.");
}
this->source_timestamp = deserializer.deserialize<int64_t>();

const auto source_gid_str = deserializer.deserialize<std::string>();
if (source_gid_str != "source_gid")
{
if (source_gid_str != "source_gid") {
throw std::runtime_error("source_gid is not found in the attachment.");
}
this->source_gid = deserializer.deserialize<std::vector<uint8_t>>();
Expand Down
55 changes: 26 additions & 29 deletions rmw_zenoh_cpp/src/detail/rmw_client_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,8 +174,7 @@ bool ClientData::init(const std::shared_ptr<zenoh::Session> & session)
zenoh::KeyExpr(liveliness_keyexpr),
zenoh::Session::LivelinessDeclarationOptions::create_default(),
&err);
if (err != Z_OK)
{
if (err != Z_OK) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to create liveliness token for the client.");
Expand Down Expand Up @@ -248,8 +247,7 @@ rmw_ret_t ClientData::take_response(

auto & reply = latest_reply->get_sample();

if(!reply.is_ok())
{
if(!reply.is_ok()) {
RMW_SET_ERROR_MSG("invalid reply sample");
return RMW_RET_ERROR;
}
Expand All @@ -258,7 +256,7 @@ rmw_ret_t ClientData::take_response(

// Object that manages the raw buffer
auto & payload = sample.get_payload();
auto slice = payload.slice_iter().next();
auto slice = payload.slice_iter().next();
if (slice.has_value()) {
const uint8_t * payload = slice.value().data;
const size_t payload_len = slice.value().len;
Expand All @@ -278,8 +276,7 @@ rmw_ret_t ClientData::take_response(
}

// Fill in the request_header
if (!sample.get_attachment().has_value())
{
if (!sample.get_attachment().has_value()) {
RMW_ZENOH_LOG_DEBUG_NAMED(
"rmw_zenoh_cpp",
"ClientData take_request attachment is empty");
Expand All @@ -296,15 +293,16 @@ rmw_ret_t ClientData::take_response(
RMW_SET_ERROR_MSG("Failed to get source_timestamp from client call attachment");
return RMW_RET_ERROR;
}
memcpy(request_header->request_id.writer_guid, attachment.source_gid.data(), RMW_GID_STORAGE_SIZE);
memcpy(request_header->request_id.writer_guid, attachment.source_gid.data(),
RMW_GID_STORAGE_SIZE);
request_header->received_timestamp = latest_reply->get_received_timestamp();

*taken = true;
} else {
RMW_ZENOH_LOG_DEBUG_NAMED(
RMW_ZENOH_LOG_DEBUG_NAMED(
"rmw_zenoh_cpp",
"ClientData not able to get slice data");
return RMW_RET_ERROR;
return RMW_RET_ERROR;
}

return RMW_RET_OK;
Expand Down Expand Up @@ -388,34 +386,34 @@ rmw_ret_t ClientData::send_request(
context_impl->session()->get(
keyexpr_.value(),
parameters,
[client_data](const zenoh::Reply& reply) {
[client_data](const zenoh::Reply & reply) {

if (!reply.is_ok()) {
RMW_ZENOH_LOG_ERROR_NAMED(
if (!reply.is_ok()) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"z_reply_is_ok returned False Reason: %s",
reply.get_err().get_payload().as_string())
return;
}
const zenoh::Sample & sample = reply.get_ok();
return;
}
const zenoh::Sample & sample = reply.get_ok();

auto sub_data = client_data.lock();
if (sub_data == nullptr) {
RMW_ZENOH_LOG_ERROR_NAMED(
auto sub_data = client_data.lock();
if (sub_data == nullptr) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to obtain ClientData from data for %s.",
std::string(sample.get_keyexpr().as_string_view()));
return;
}
return;
}

if (sub_data->is_shutdown()) {
return;
}
if (sub_data->is_shutdown()) {
return;
}

std::chrono::nanoseconds::rep received_timestamp =
std::chrono::system_clock::now().time_since_epoch().count();
std::chrono::nanoseconds::rep received_timestamp =
std::chrono::system_clock::now().time_since_epoch().count();

sub_data->add_new_reply(
sub_data->add_new_reply(
std::make_unique<rmw_zenoh_cpp::ZenohReply>(reply, received_timestamp));
},
zenoh::closures::none,
Expand Down Expand Up @@ -478,8 +476,7 @@ void ClientData::_shutdown()
// Unregister this node from the ROS graph.
zenoh::ZResult err;
std::move(token_).value().undeclare(&err);
if (err != Z_OK)
{
if (err != Z_OK) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to undeclare liveliness token");
Expand Down
51 changes: 27 additions & 24 deletions rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ class rmw_context_impl_s::Data final
// Check if shm is enabled.
std::string shm_enabled = config.value().get(Z_CONFIG_SHARED_MEMORY_KEY, &result);
if (result != Z_OK) {
RMW_ZENOH_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Not able to get %s from the config file",
Z_CONFIG_SHARED_MEMORY_KEY);
Expand Down Expand Up @@ -133,7 +133,8 @@ class rmw_context_impl_s::Data final
}

// Initialize the graph cache.
graph_cache_ = std::make_shared<rmw_zenoh_cpp::GraphCache>(this->session_->get_zid().to_string());
graph_cache_ =
std::make_shared<rmw_zenoh_cpp::GraphCache>(this->session_->get_zid().to_string());
// Setup liveliness subscriptions for discovery.
std::string liveliness_str = rmw_zenoh_cpp::liveliness::subscription_token(domain_id);

Expand Down Expand Up @@ -169,24 +170,26 @@ class rmw_context_impl_s::Data final
zenoh::Session::LivelinessGetOptions::create_default(),
&err);

if (err != Z_OK)
{
if (err != Z_OK) {
throw std::runtime_error("Error getting liveliness. ");
}

for (auto res = replies.recv(); std::holds_alternative<zenoh::Reply>(res); res = replies.recv()) {
for (auto res = replies.recv(); std::holds_alternative<zenoh::Reply>(res);
res = replies.recv())
{

const zenoh::Reply &reply = std::get<zenoh::Reply>(res);
if (reply.is_ok()) {
const auto &sample = reply.get_ok();
graph_cache_->parse_put(std::string(sample.get_keyexpr().as_string_view()), true);
}
const zenoh::Reply & reply = std::get<zenoh::Reply>(res);
if (reply.is_ok()) {
const auto & sample = reply.get_ok();
graph_cache_->parse_put(std::string(sample.get_keyexpr().as_string_view()), true);
}
}

// Initialize the shm manager if shared_memory is enabled in the config.
shm_provider_ = std::nullopt;
if (shm_enabled == "true") {
auto layout = zenoh::MemoryLayout(SHM_BUFFER_SIZE_MB * 1024 * 1024, zenoh::AllocAlignment({5}));
auto layout = zenoh::MemoryLayout(SHM_BUFFER_SIZE_MB * 1024 * 1024,
zenoh::AllocAlignment({5}));
zenoh::PosixShmProvider provider(layout, &result);
if (result != Z_OK) {
throw std::runtime_error("Unable to create shm provider.");
Expand All @@ -207,21 +210,22 @@ class rmw_context_impl_s::Data final
sub_options.history = true;
graph_subscriber_cpp_ = session_->liveliness_declare_subscriber(
keyexpr_cpp,
[&](const zenoh::Sample& sample) {
[&](const zenoh::Sample & sample) {

// // Look up the data shared_ptr in the global map. If it is in there, use it.
// If not, it is being shutdown so we can just ignore this update.
std::shared_ptr<rmw_context_impl_s::Data> data_shared_ptr{nullptr};
{
std::lock_guard<std::mutex> lk(data_to_data_shared_ptr_map_mutex);
if (data_to_data_shared_ptr_map.count(this) == 0) {
return;
}
data_shared_ptr = data_to_data_shared_ptr_map[this];
std::shared_ptr<rmw_context_impl_s::Data> data_shared_ptr{nullptr};
{
std::lock_guard<std::mutex> lk(data_to_data_shared_ptr_map_mutex);
if (data_to_data_shared_ptr_map.count(this) == 0) {
return;
}
data_shared_ptr = data_to_data_shared_ptr_map[this];
}

// Update the graph cache.
data_shared_ptr->update_graph_cache(sample, std::string(sample.get_keyexpr().as_string_view()));
data_shared_ptr->update_graph_cache(sample,
std::string(sample.get_keyexpr().as_string_view()));
},
zenoh::closures::none,
std::move(sub_options),
Expand Down Expand Up @@ -257,8 +261,7 @@ class rmw_context_impl_s::Data final

zenoh::ZResult err;
std::move(graph_subscriber_cpp_).value().undeclare(&err);
if (err != Z_OK)
{
if (err != Z_OK) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to undeclare liveliness token");
Expand Down Expand Up @@ -378,7 +381,7 @@ class rmw_context_impl_s::Data final
nodes_.erase(node);
}

void update_graph_cache(const zenoh::Sample& sample_kind, const std::string & keystr)
void update_graph_cache(const zenoh::Sample & sample_kind, const std::string & keystr)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
if (is_shutdown_) {
Expand Down Expand Up @@ -468,7 +471,7 @@ std::string rmw_context_impl_s::enclave() const
///=============================================================================
const std::shared_ptr<zenoh::Session> rmw_context_impl_s::session() const
{
return data_->session();
return data_->session();
}

///=============================================================================
Expand Down
6 changes: 2 additions & 4 deletions rmw_zenoh_cpp/src/detail/rmw_node_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,7 @@ std::shared_ptr<NodeData> NodeData::make(
zenoh::KeyExpr(liveliness_keyexpr),
zenoh::Session::LivelinessDeclarationOptions::create_default(),
&err);
if (err != Z_OK)
{
if (err != Z_OK) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to create liveliness token for the node.");
Expand Down Expand Up @@ -402,8 +401,7 @@ rmw_ret_t NodeData::shutdown()
// Unregister this node from the ROS graph.
zenoh::ZResult err;
std::move(token_).value().undeclare(&err);
if (err != Z_OK)
{
if (err != Z_OK) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to undeclare liveliness token");
Expand Down
15 changes: 5 additions & 10 deletions rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,8 +116,7 @@ std::shared_ptr<PublisherData> PublisherData::make(

pub_cache = session->declare_publication_cache(pub_ke, std::move(pub_cache_opts), &err);

if (err != Z_OK)
{
if (err != Z_OK) {
RMW_SET_ERROR_MSG("unable to create zenoh publisher cache");
return nullptr;
}
Expand All @@ -136,8 +135,7 @@ std::shared_ptr<PublisherData> PublisherData::make(
}
auto pub = session->declare_publisher(pub_ke, std::move(opts), &err);

if (err != Z_OK)
{
if (err != Z_OK) {
RMW_SET_ERROR_MSG("Unable to create Zenoh publisher.");
return nullptr;
}
Expand All @@ -147,8 +145,7 @@ std::shared_ptr<PublisherData> PublisherData::make(
zenoh::KeyExpr(liveliness_keyexpr),
zenoh::Session::LivelinessDeclarationOptions::create_default(),
&err);
if (err != Z_OK)
{
if (err != Z_OK) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to create liveliness token for the publisher.");
Expand Down Expand Up @@ -392,16 +389,14 @@ rmw_ret_t PublisherData::shutdown()
// Unregister this publisher from the ROS graph.
zenoh::ZResult err;
std::move(token_).value().undeclare(&err);
if (err != Z_OK)
{
if (err != Z_OK) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to undeclare liveliness token");
return RMW_RET_ERROR;
}
std::move(pub_).undeclare(&err);
if (err != Z_OK)
{
if (err != Z_OK) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to undeclare publisher");
Expand Down
Loading

0 comments on commit da108bf

Please sign in to comment.