diff --git a/rmw_zenoh_cpp/src/detail/attachment_helpers.cpp b/rmw_zenoh_cpp/src/detail/attachment_helpers.cpp index a9dff235..62fda915 100644 --- a/rmw_zenoh_cpp/src/detail/attachment_helpers.cpp +++ b/rmw_zenoh_cpp/src/detail/attachment_helpers.cpp @@ -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]); } } @@ -63,22 +62,19 @@ AttachmentData::AttachmentData(const zenoh::Bytes & attachment) { zenoh::ext::Deserializer deserializer(std::move(attachment)); const auto sequence_number_str = deserializer.deserialize(); - 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(); const auto source_timestamp_str = deserializer.deserialize(); - 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(); const auto source_gid_str = deserializer.deserialize(); - 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>(); diff --git a/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp index 5f7bbc9c..9accc6ff 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp @@ -174,8 +174,7 @@ bool ClientData::init(const std::shared_ptr & 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."); @@ -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; } @@ -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; @@ -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"); @@ -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; @@ -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(reply, received_timestamp)); }, zenoh::closures::none, @@ -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"); diff --git a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp index d457b325..c1c61ad3 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp @@ -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); @@ -133,7 +133,8 @@ class rmw_context_impl_s::Data final } // Initialize the graph cache. - graph_cache_ = std::make_shared(this->session_->get_zid().to_string()); + graph_cache_ = + std::make_shared(this->session_->get_zid().to_string()); // Setup liveliness subscriptions for discovery. std::string liveliness_str = rmw_zenoh_cpp::liveliness::subscription_token(domain_id); @@ -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(res); res = replies.recv()) { + for (auto res = replies.recv(); std::holds_alternative(res); + res = replies.recv()) + { - const zenoh::Reply &reply = std::get(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(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."); @@ -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 data_shared_ptr{nullptr}; - { - std::lock_guard 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 data_shared_ptr{nullptr}; + { + std::lock_guard 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), @@ -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"); @@ -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 lock(mutex_); if (is_shutdown_) { @@ -468,7 +471,7 @@ std::string rmw_context_impl_s::enclave() const ///============================================================================= const std::shared_ptr rmw_context_impl_s::session() const { -return data_->session(); + return data_->session(); } ///============================================================================= diff --git a/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp index 4e6622e8..1ec650d4 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp @@ -63,8 +63,7 @@ std::shared_ptr 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."); @@ -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"); diff --git a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp index 6614a9df..bd8bad8a 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp @@ -116,8 +116,7 @@ std::shared_ptr 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; } @@ -136,8 +135,7 @@ std::shared_ptr 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; } @@ -147,8 +145,7 @@ std::shared_ptr 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."); @@ -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"); diff --git a/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp index 918699d9..fc02e9ae 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp @@ -135,26 +135,27 @@ std::shared_ptr ServiceData::make( return nullptr; } - zenoh::Session::QueryableOptions qable_options = zenoh::Session::QueryableOptions::create_default(); + zenoh::Session::QueryableOptions qable_options = + zenoh::Session::QueryableOptions::create_default(); qable_options.complete = true; std::weak_ptr data_wp = service_data; service_data->qable_ = session->declare_queryable( service_ke, - [data_wp](const zenoh::Query& query){ - auto sub_data = data_wp.lock(); - if (sub_data == nullptr) { - RMW_ZENOH_LOG_ERROR_NAMED( + [data_wp](const zenoh::Query & query){ + auto sub_data = data_wp.lock(); + if (sub_data == nullptr) { + RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "Unable to obtain ServiceData from data for %s.", std::string(query.get_keyexpr().as_string_view())); - return; - } + 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_query(std::make_unique(query, received_timestamp)); + sub_data->add_new_query(std::make_unique(query, received_timestamp)); }, zenoh::closures::none, std::move(qable_options), @@ -169,8 +170,7 @@ std::shared_ptr ServiceData::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 service."); @@ -262,15 +262,14 @@ rmw_ret_t ServiceData::take_request( // DESERIALIZE MESSAGE ======================================================== auto payload = loaned_query.get_payload(); - if (!payload.has_value()) - { + if (!payload.has_value()) { RMW_ZENOH_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "ServiceData take_request payload is empty"); return RMW_RET_ERROR; } - auto slice = payload.value().get().slice_iter().next(); + auto slice = payload.value().get().slice_iter().next(); if (slice.has_value()) { const uint8_t * payload = slice.value().data; @@ -293,15 +292,15 @@ rmw_ret_t ServiceData::take_request( // Fill in the request header. // Get the sequence_number out of the attachment - if (!loaned_query.get_attachment().has_value()) - { + if (!loaned_query.get_attachment().has_value()) { RMW_ZENOH_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "ServiceData take_request attachment is empty"); return RMW_RET_ERROR; } - rmw_zenoh_cpp::AttachmentData attachment(std::move(loaned_query.get_attachment().value().get())); + rmw_zenoh_cpp::AttachmentData attachment(std::move( + loaned_query.get_attachment().value().get())); request_header->request_id.sequence_number = attachment.sequence_number; if (request_header->request_id.sequence_number < 0) { @@ -309,7 +308,8 @@ rmw_ret_t ServiceData::take_request( 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->source_timestamp = attachment.source_timestamp; if (request_header->source_timestamp < 0) { @@ -336,10 +336,10 @@ rmw_ret_t ServiceData::take_request( it->second.insert(std::make_pair(request_header->request_id.sequence_number, std::move(query))); *taken = true; } else { - RMW_ZENOH_LOG_DEBUG_NAMED( + RMW_ZENOH_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "ServiceData not able to get slice data"); - return RMW_RET_ERROR; + return RMW_RET_ERROR; } return RMW_RET_OK; } @@ -493,8 +493,7 @@ rmw_ret_t ServiceData::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"); @@ -502,8 +501,7 @@ rmw_ret_t ServiceData::shutdown() } std::move(qable_).value().undeclare(&err); - if (err != Z_OK) - { + if (err != Z_OK) { RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "Unable to undeclare liveliness token"); diff --git a/rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp index 6790cda4..14f92c69 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp @@ -167,8 +167,7 @@ bool SubscriptionData::init() zenoh::ZResult err; zenoh::KeyExpr sub_ke(entity_->topic_info()->topic_keyexpr_, true, &err); - if (err != Z_OK) - { + if (err != Z_OK) { RMW_SET_ERROR_MSG("unable to create zenoh keyexpr."); return false; } @@ -180,7 +179,8 @@ bool SubscriptionData::init() // TODO(Yadunund): Rely on a separate function to return the sub // as we start supporting more qos settings. if (entity_->topic_info()->qos_.durability == RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL) { - zenoh::Session::QueryingSubscriberOptions sub_options = zenoh::Session::QueryingSubscriberOptions::create_default(); + zenoh::Session::QueryingSubscriberOptions sub_options = + zenoh::Session::QueryingSubscriberOptions::create_default(); const std::string selector = "*/" + entity_->topic_info()->topic_keyexpr_; zenoh::KeyExpr selector_ke(selector); sub_options.query_keyexpr = std::move(selector_ke); @@ -194,12 +194,13 @@ bool SubscriptionData::init() // We set consolidation to none as we need to receive transient local messages // from a number of publishers. Eg: To receive TF data published over /tf_static // by various publishers. - sub_options.query_consolidation = zenoh::QueryConsolidation(zenoh::ConsolidationMode::Z_CONSOLIDATION_MODE_NONE); + sub_options.query_consolidation = + zenoh::QueryConsolidation(zenoh::ConsolidationMode::Z_CONSOLIDATION_MODE_NONE); std::weak_ptr data_wp = shared_from_this(); auto sub = context_impl->session()->declare_querying_subscriber( sub_ke, - [data_wp](const zenoh::Sample& sample) { + [data_wp](const zenoh::Sample & sample) { auto sub_data = data_wp.lock(); if (sub_data == nullptr) { RMW_ZENOH_LOG_ERROR_NAMED( @@ -210,8 +211,7 @@ bool SubscriptionData::init() } auto attachment = sample.get_attachment(); - if (!attachment.has_value()) - { + if (!attachment.has_value()) { RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "Unable to obtain attachment") @@ -231,8 +231,7 @@ bool SubscriptionData::init() zenoh::closures::none, std::move(sub_options), &err); - if (err != Z_OK) - { + if (err != Z_OK) { RMW_SET_ERROR_MSG("unable to create zenoh subscription"); return false; } @@ -256,8 +255,8 @@ bool SubscriptionData::init() std::lock_guard lock(sub_data->mutex_); const std::string selector = queryable_prefix + - "/" + - sub_data->entity_->topic_info().value().topic_keyexpr_; + "/" + + sub_data->entity_->topic_info().value().topic_keyexpr_; RMW_ZENOH_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "QueryingSubscriberCallback triggered over %s.", @@ -274,15 +273,15 @@ bool SubscriptionData::init() std::move(opts), &err); - if (err != Z_OK) - { + if (err != Z_OK) { RMW_SET_ERROR_MSG("unable to get querying subscriber."); return; } } ); } else { - zenoh::Session::SubscriberOptions sub_options = zenoh::Session::SubscriberOptions::create_default(); + zenoh::Session::SubscriberOptions sub_options = + zenoh::Session::SubscriberOptions::create_default(); std::weak_ptr data_wp = shared_from_this(); zenoh::Subscriber sub = context_impl->session()->declare_subscriber( sub_ke, @@ -299,8 +298,7 @@ bool SubscriptionData::init() return; } auto attachment = sample.get_attachment(); - if (!attachment.has_value()) - { + if (!attachment.has_value()) { RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "Unable to obtain attachment") @@ -320,8 +318,7 @@ bool SubscriptionData::init() zenoh::closures::none, std::move(sub_options), &err); - if (err != Z_OK) - { + if (err != Z_OK) { RMW_SET_ERROR_MSG("unable to create zenoh subscription"); return false; } @@ -334,8 +331,7 @@ bool SubscriptionData::init() 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 subscription."); @@ -401,32 +397,29 @@ rmw_ret_t SubscriptionData::shutdown() // Unregister this subscription 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; } - if (sub_.has_value()) - { + if (sub_.has_value()) { zenoh::Subscriber * sub = std::get_if>(&sub_.value()); if (sub != nullptr) { std::move(*sub).undeclare(&err); - if (err != Z_OK) - { + if (err != Z_OK) { RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "failed to undeclare sub."); return RMW_RET_ERROR; } } else { - zenoh::ext::QueryingSubscriber * sub = std::get_if>(&sub_.value()); + zenoh::ext::QueryingSubscriber * sub = + std::get_if>(&sub_.value()); if (sub != nullptr) { std::move(*sub).undeclare(&err); - if (err != Z_OK) - { + if (err != Z_OK) { RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "failed to undeclare querying sub."); @@ -517,7 +510,8 @@ rmw_ret_t SubscriptionData::take_one_message( // TODO(clalancette): fill in reception_sequence_number message_info->reception_sequence_number = 0; message_info->publisher_gid.implementation_identifier = rmw_zenoh_cpp::rmw_zenoh_identifier; - memcpy(message_info->publisher_gid.data, msg_data->attachment.source_gid.data(), RMW_GID_STORAGE_SIZE); + memcpy(message_info->publisher_gid.data, msg_data->attachment.source_gid.data(), + RMW_GID_STORAGE_SIZE); message_info->from_intra_process = false; } *taken = true; @@ -571,7 +565,8 @@ rmw_ret_t SubscriptionData::take_serialized_message( // TODO(clalancette): fill in reception_sequence_number message_info->reception_sequence_number = 0; message_info->publisher_gid.implementation_identifier = rmw_zenoh_cpp::rmw_zenoh_identifier; - memcpy(message_info->publisher_gid.data, msg_data->attachment.source_gid.data(), RMW_GID_STORAGE_SIZE); + memcpy(message_info->publisher_gid.data, msg_data->attachment.source_gid.data(), + RMW_GID_STORAGE_SIZE); message_info->from_intra_process = false; } } else { diff --git a/rmw_zenoh_cpp/src/detail/zenoh_utils.cpp b/rmw_zenoh_cpp/src/detail/zenoh_utils.cpp index 86fc887e..13d29b44 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_utils.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_utils.cpp @@ -23,7 +23,7 @@ namespace rmw_zenoh_cpp { ///============================================================================= zenoh::Bytes create_map_and_set_sequence_num( - int64_t sequence_number, uint8_t gid[RMW_GID_STORAGE_SIZE]) + int64_t sequence_number, uint8_t gid[RMW_GID_STORAGE_SIZE]) { auto now = std::chrono::system_clock::now().time_since_epoch(); auto now_ns = std::chrono::duration_cast(now); diff --git a/rmw_zenoh_cpp/src/detail/zenoh_utils.hpp b/rmw_zenoh_cpp/src/detail/zenoh_utils.hpp index a52e20c7..641387dd 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_utils.hpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_utils.hpp @@ -26,7 +26,7 @@ namespace rmw_zenoh_cpp { ///============================================================================= zenoh::Bytes create_map_and_set_sequence_num( - int64_t sequence_number, uint8_t gid[RMW_GID_STORAGE_SIZE]); + int64_t sequence_number, uint8_t gid[RMW_GID_STORAGE_SIZE]); ///============================================================================= // A class to store the replies to service requests. diff --git a/rmw_zenoh_cpp/src/zenohd/main.cpp b/rmw_zenoh_cpp/src/zenohd/main.cpp index 987aa541..b32eca79 100644 --- a/rmw_zenoh_cpp/src/zenohd/main.cpp +++ b/rmw_zenoh_cpp/src/zenohd/main.cpp @@ -80,8 +80,8 @@ int main(int argc, char ** argv) zenoh::Session::SessionOptions::create_default(), &result); if(result != Z_OK) { - std::cout << "Error opening Session!" << "\\n"; - return 1; + std::cout << "Error opening Session!" << "\\n"; + return 1; } std::cout << "Started Zenoh router with id"