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 25, 2024
1 parent f9d06d5 commit fc702f1
Show file tree
Hide file tree
Showing 6 changed files with 44 additions and 33 deletions.
24 changes: 13 additions & 11 deletions rmw_zenoh_cpp/src/detail/rmw_client_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,15 +295,17 @@ 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_cpp",
"ClientData not able to get slice data");
"rmw_zenoh_cpp",
"ClientData not able to get slice data");
return RMW_RET_ERROR;
}

Expand Down Expand Up @@ -391,19 +393,19 @@ rmw_ret_t ClientData::send_request(
[client_data](const zenoh::Reply & reply) {
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())
"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();

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()));
"rmw_zenoh_cpp",
"Unable to obtain ClientData from data for %s.",
std::string(sample.get_keyexpr().as_string_view()));
return;
}

Expand All @@ -415,7 +417,7 @@ rmw_ret_t ClientData::send_request(
std::chrono::system_clock::now().time_since_epoch().count();

sub_data->add_new_reply(
std::make_unique<rmw_zenoh_cpp::ZenohReply>(reply, received_timestamp));
std::make_unique<rmw_zenoh_cpp::ZenohReply>(reply, received_timestamp));
},
zenoh::closures::none,
std::move(opts),
Expand Down
8 changes: 4 additions & 4 deletions rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ class rmw_context_impl_s::Data final
{
// Initialize the zenoh configuration.
std::optional<zenoh::Config> config = rmw_zenoh_cpp::get_z_config(
rmw_zenoh_cpp::ConfigurableEntity::Session);
rmw_zenoh_cpp::ConfigurableEntity::Session);

if (!config.has_value()) {
throw std::runtime_error("Error configuring Zenoh session.");
Expand All @@ -95,9 +95,9 @@ class rmw_context_impl_s::Data final

// Initialize the zenoh session.
session_ = std::make_shared<zenoh::Session>(
std::move(config.value()),
zenoh::Session::SessionOptions::create_default(),
&result);
std::move(config.value()),
zenoh::Session::SessionOptions::create_default(),
&result);
if(result != Z_OK) {
throw std::runtime_error("Error setting up zenoh session. ");
}
Expand Down
8 changes: 5 additions & 3 deletions rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,7 +269,9 @@ rmw_ret_t PublisherData::publish(
entity_->copy_gid(local_gid);
zenoh::ZResult err;
auto options = zenoh::Publisher::PutOptions::create_default();
options.attachment = create_map_and_set_sequence_num(sequence_number_++, local_gid);
options.attachment = create_map_and_set_sequence_num(
sequence_number_++,
local_gid);

// TODO(ahcorde): shmbuf
std::vector<uint8_t> raw_image(
Expand Down Expand Up @@ -398,8 +400,8 @@ rmw_ret_t PublisherData::shutdown()
std::move(pub_).undeclare(&err);
if (err != Z_OK) {
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to undeclare publisher");
"rmw_zenoh_cpp",
"Unable to undeclare publisher");
return RMW_RET_ERROR;
}

Expand Down
10 changes: 6 additions & 4 deletions rmw_zenoh_cpp/src/detail/rmw_service_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,8 @@ std::shared_ptr<ServiceData> ServiceData::make(
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.",
"rmw_zenoh_cpp",
"Unable to obtain ServiceData from data for %s.",
std::string(query.get_keyexpr().as_string_view()));
return;
}
Expand Down Expand Up @@ -310,8 +310,10 @@ 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) {
Expand Down
19 changes: 12 additions & 7 deletions rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,9 +269,10 @@ bool SubscriptionData::init()

zenoh::ZResult err;
std::get<zenoh::ext::QueryingSubscriber<void>>(
sub_data->sub_.value()).get(zenoh::KeyExpr(selector),
std::move(opts),
&err);
sub_data->sub_.value()).get(
zenoh::KeyExpr(selector),
std::move(opts),
&err);

if (err != Z_OK) {
RMW_SET_ERROR_MSG("unable to get querying subscriber.");
Expand Down Expand Up @@ -508,8 +509,10 @@ 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;
Expand Down Expand Up @@ -563,8 +566,10 @@ 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 {
Expand Down
8 changes: 4 additions & 4 deletions rmw_zenoh_cpp/src/zenohd/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ int main(int argc, char ** argv)
zenoh::try_init_log_from_env();

std::optional<zenoh::Config> config = rmw_zenoh_cpp::get_z_config(
rmw_zenoh_cpp::ConfigurableEntity::Router);
rmw_zenoh_cpp::ConfigurableEntity::Router);

if (!config.has_value()) {
RMW_SET_ERROR_MSG("Error configuring Zenoh router.");
Expand All @@ -76,9 +76,9 @@ int main(int argc, char ** argv)

zenoh::ZResult result;
auto session = zenoh::Session::open(
std::move(config.value()),
zenoh::Session::SessionOptions::create_default(),
&result);
std::move(config.value()),
zenoh::Session::SessionOptions::create_default(),
&result);
if(result != Z_OK) {
std::cout << "Error opening Session!" << "\\n";
return 1;
Expand Down

0 comments on commit fc702f1

Please sign in to comment.