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

Set Debug Logs #22

Merged
merged 2 commits into from
Sep 2, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
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
2 changes: 1 addition & 1 deletion rmw_zenoh_cpp/src/impl/client_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,6 @@ void rmw_client_data_t::zn_service_availability_query_callback(const zn_source_i
== rmw_client_data_t::zn_availability_query_responses_.end()) {
rmw_client_data_t::zn_availability_query_responses_.insert(key);
} else {
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "zenoh availability for %s already set", key.c_str());
RCUTILS_LOG_WARN_NAMED("rmw_zenoh_cpp", "zenoh availability for %s already set", key.c_str());
}
}
24 changes: 8 additions & 16 deletions rmw_zenoh_cpp/src/impl/wait_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,37 +15,29 @@ bool check_wait_conditions(
{
// Subscriptions: If there are subscription messages ready, continue
if (!rmw_subscription_data_t::zn_messages_.empty()) {
// RCUTILS_LOG_INFO_NAMED(
// "rmw_zenoh_cpp",
// "[rmw_wait] SUBSCRIPTION MESSAGES IN QUEUE: %ld", rmw_subscription_data_t::zn_messages_.size()
// );
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_wait] SUBSCRIPTION MESSAGES IN QUEUE: %ld",
rmw_subscription_data_t::zn_messages_.size());
return true;
}

// Services: If there are request messages ready, continue
if (!rmw_service_data_t::zn_request_messages_.empty()) {
// RCUTILS_LOG_INFO_NAMED(
// "rmw_zenoh_cpp",
// "[rmw_wait] REQUEST MESSAGES IN QUEUE: %ld", rmw_service_data_t::zn_request_messages_.size()
// );
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_wait] REQUEST MESSAGES IN QUEUE: %ld",
rmw_service_data_t::zn_request_messages_.size());
return true;
}

// Clients: If there are response messages ready, continue
if (!rmw_client_data_t::zn_response_messages_.empty()) {
// RCUTILS_LOG_INFO_NAMED(
// "rmw_zenoh_cpp",
// "[rmw_wait] RESPONSE MESSAGES IN QUEUE: %ld", rmw_client_data_t::zn_response_messages_.size()
// );
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_wait] RESPONSE MESSAGES IN QUEUE: %ld",
rmw_client_data_t::zn_response_messages_.size());
return true;
}

// Clients: If there are service server availabiity messages ready, continue
if (!rmw_client_data_t::zn_availability_query_responses_.empty()) {
// RCUTILS_LOG_INFO_NAMED(
// "rmw_zenoh_cpp",
// "[rmw_wait] RESPONSE MESSAGES IN QUEUE: %ld", rmw_client_data_t::zn_availability_query_responses_.size()
// );
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_wait] AVAILABILITY QUERY RESPONSES: %ld",
rmw_client_data_t::zn_availability_query_responses_.size());
return true;
}

Expand Down
20 changes: 10 additions & 10 deletions rmw_zenoh_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@ rmw_service_server_is_available(
{
*result = false;

RCUTILS_LOG_INFO_NAMED(
"rmw_zenoh_cpp", "[rmw_service_server_is_available] %s", client->service_name);
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_service_server_is_available] %s",
client->service_name);

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_INVALID_ARGUMENT);
Expand All @@ -52,7 +52,7 @@ rmw_service_server_is_available(
// Check if server is alive by querying its availability Zenoh queryable
zn_query(client_data->zn_session_,
client->service_name,
"", // NOTE(CH3): Maybe use this predicate we want to more things in the queryable
"", // NOTE(CH3): Maybe use this predicate if we want to more things in the queryable
zn_query_target_default(),
zn_query_consolidation_default(),
rmw_client_data_t::zn_service_availability_query_callback);
Expand All @@ -77,7 +77,7 @@ rmw_create_client(
const char * service_name,
const rmw_qos_profile_t * qos_profile)
{
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "[rmw_create_client] %s", service_name);
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_create_client] %s", service_name);

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(node, nullptr);
Expand Down Expand Up @@ -262,7 +262,7 @@ rmw_create_client(
rmw_ret_t
rmw_destroy_client(rmw_node_t * node, rmw_client_t * client)
{
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "[rmw_destroy_client] %s", client->service_name);
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_destroy_client] %s", client->service_name);

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_INVALID_ARGUMENT);
Expand Down Expand Up @@ -303,10 +303,10 @@ rmw_destroy_client(rmw_node_t * node, rmw_client_t * client)
rmw_ret_t
rmw_send_request(const rmw_client_t * client, const void * ros_request, int64_t * sequence_id)
{
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp",
"[rmw_send_request] %s (%ld)",
static_cast<rmw_client_data_t *>(client->data)->zn_request_topic_key_,
static_cast<rmw_client_data_t *>(client->data)->zn_request_topic_id_);
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp",
"[rmw_send_request] %s (%ld)",
static_cast<rmw_client_data_t *>(client->data)->zn_request_topic_key_,
static_cast<rmw_client_data_t *>(client->data)->zn_request_topic_id_);

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(client, RMW_RET_INVALID_ARGUMENT);
Expand Down Expand Up @@ -427,7 +427,7 @@ rmw_take_response(
// This tells rcl that the check for a new message was done, but no messages have come in yet.
return RMW_RET_OK;
}
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "[rmw_take_response] Response found: %s", key.c_str());
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_take_response] Response found: %s", key.c_str());

auto response_bytes = client_data->zn_response_messages_[key];

Expand Down
6 changes: 3 additions & 3 deletions rmw_zenoh_cpp/src/rmw_event.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ rmw_take_event(const rmw_event_t * event_handle, void * event_info, bool * taken
(void)event_handle;
(void)event_info;

// RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "rmw_take_event (STUB)");
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_take_event (STUB)");
*taken = true;

return RMW_RET_OK;
Expand All @@ -30,7 +30,7 @@ rmw_publisher_event_init(
const rmw_publisher_t * publisher,
rmw_event_type_t event_type)
{
// RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "rmw_publisher_event_init (STUB)");
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_publisher_event_init (STUB)");

RMW_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(event, RMW_RET_INVALID_ARGUMENT);
Expand Down Expand Up @@ -63,7 +63,7 @@ rmw_subscription_event_init(
const rmw_subscription_t * subscription,
rmw_event_type_t event_type)
{
// RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "rmw_subscription_event_init");
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_subscription_event_init");

RMW_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(event, RMW_RET_INVALID_ARGUMENT);
Expand Down
6 changes: 3 additions & 3 deletions rmw_zenoh_cpp/src/rmw_guard_conditions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ extern "C"
rmw_guard_condition_t *
rmw_create_guard_condition(rmw_context_t * context)
{
// RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "rmw_create_guard_condition");
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_create_guard_condition");

RMW_CHECK_ARGUMENT_FOR_NULL(context, nullptr);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(context,
Expand All @@ -42,7 +42,7 @@ rmw_create_guard_condition(rmw_context_t * context)
rmw_ret_t
rmw_destroy_guard_condition(rmw_guard_condition_t * guard_condition_handle)
{
// RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "rmw_destroy_guard_condition");
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_destroy_guard_condition");

if (guard_condition_handle) {
delete static_cast<GuardCondition *>(guard_condition_handle->data);
Expand All @@ -57,7 +57,7 @@ rmw_destroy_guard_condition(rmw_guard_condition_t * guard_condition_handle)
rmw_ret_t
rmw_trigger_guard_condition(const rmw_guard_condition_t * guard_condition_handle)
{
// RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "rmw_trigger_guard_condition");
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_trigger_guard_condition");

RMW_CHECK_ARGUMENT_FOR_NULL(guard_condition_handle, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(guard_condition_handle,
Expand Down
2 changes: 1 addition & 1 deletion rmw_zenoh_cpp/src/rmw_implementation_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ rmw_get_implementation_identifier()
const char *
rmw_get_serialization_format()
{
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "rmw_get_serialization_format");
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_get_serialization_format");
return nullptr;
}

Expand Down
6 changes: 6 additions & 0 deletions rmw_zenoh_cpp/src/rmw_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@ extern "C"
rmw_ret_t
rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
{
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_init");

// ASSERTIONS ================================================================
// Check context
RMW_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
Expand Down Expand Up @@ -123,6 +125,8 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context)
rmw_ret_t
rmw_shutdown(rmw_context_t * context)
{
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_shutdown");

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_FOR_NULL_WITH_MSG(context->impl,
Expand All @@ -148,6 +152,8 @@ rmw_shutdown(rmw_context_t * context)
rmw_ret_t
rmw_context_fini(rmw_context_t * context)
{
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_context_fini");

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_FOR_NULL_WITH_MSG(context->impl,
Expand Down
6 changes: 6 additions & 0 deletions rmw_zenoh_cpp/src/rmw_init_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@ extern "C"
rmw_ret_t
rmw_init_options_init(rmw_init_options_t * init_options, rcutils_allocator_t allocator)
{
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_init_options_init");

RMW_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ALLOCATOR(&allocator, return RMW_RET_INVALID_ARGUMENT);

Expand Down Expand Up @@ -124,6 +126,8 @@ rmw_init_options_init(rmw_init_options_t * init_options, rcutils_allocator_t all
rmw_ret_t
rmw_init_options_copy(const rmw_init_options_t * src, rmw_init_options_t * dst)
{
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_init_options_copy");

RMW_CHECK_ARGUMENT_FOR_NULL(src, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(dst, RMW_RET_INVALID_ARGUMENT);
if (nullptr == src->implementation_identifier) {
Expand Down Expand Up @@ -199,6 +203,8 @@ rmw_init_options_copy(const rmw_init_options_t * src, rmw_init_options_t * dst)
rmw_ret_t
rmw_init_options_fini(rmw_init_options_t * init_options)
{
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_init_options_fini");

assert(eclipse_zenoh_identifier != NULL);

RMW_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT);
Expand Down
7 changes: 6 additions & 1 deletion rmw_zenoh_cpp/src/rmw_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@ rmw_create_node(
(void)domain_id;
(void)localhost_only;

RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_create_node] %s", name);

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(context, nullptr);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(context,
Expand Down Expand Up @@ -159,7 +161,6 @@ rmw_create_node(
// return nullptr;
// }

// RCUTILS_LOG_INFO("CREATED NODE %s", node->name);
return node;
}

Expand All @@ -178,6 +179,8 @@ rmw_destroy_node(rmw_node_t * node)
// NOTE(CH3) TODO(CH3): Again, no graph updates are implemented yet
// I am not sure how this will work with Zenoh

RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_destroy_node] %s", node->name);

// OBTAIN ALLOCATOR ==========================================================
rcutils_allocator_t * allocator = &node->context->options.allocator;

Expand All @@ -201,6 +204,8 @@ rmw_destroy_node(rmw_node_t * node)
const rmw_guard_condition_t *
rmw_node_get_graph_guard_condition(const rmw_node_t * node)
{
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_node_get_graph_guard_condition");

RMW_CHECK_ARGUMENT_FOR_NULL(node->data, nullptr);
return static_cast<rmw_node_impl_t *>(node->data)->graph_guard_condition_;
}
Expand Down
6 changes: 3 additions & 3 deletions rmw_zenoh_cpp/src/rmw_publish.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,9 @@ rmw_publish(
rmw_publisher_allocation_t * allocation)
{
(void) allocation;
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "[rmw_publish] %s (%ld)",
publisher->topic_name,
static_cast<rmw_publisher_data_t *>(publisher->data)->zn_topic_id_);
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_publish] %s (%ld)",
publisher->topic_name,
static_cast<rmw_publisher_data_t *>(publisher->data)->zn_topic_id_);

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_INVALID_ARGUMENT);
Expand Down
12 changes: 8 additions & 4 deletions rmw_zenoh_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ rmw_create_publisher(
const rmw_qos_profile_t * qos_profile,
const rmw_publisher_options_t * publisher_options)
{
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "[rmw_create_publisher] %s", topic_name);
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_create_publisher] %s", topic_name);

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(node, nullptr);
Expand Down Expand Up @@ -136,7 +136,10 @@ rmw_create_publisher(
publisher_data->zn_session_ = s;
publisher_data->typesupport_identifier_ = type_support->typesupport_identifier;
publisher_data->type_support_impl_ = type_support->data;
// RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "[rmw_create_publisher] Zenoh resource declared: %s (%ld)", topic_name, publisher_data->zn_topic_id);
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp",
"[rmw_create_publisher] Zenoh resource declared: %s (%ld)",
topic_name,
publisher_data->zn_topic_id_);

// Allocate and in-place assign new message typesupport instance
publisher_data->type_support_ = static_cast<rmw_zenoh_cpp::MessageTypeSupport *>(
Expand Down Expand Up @@ -182,6 +185,8 @@ rmw_destroy_publisher(rmw_node_t * node, rmw_publisher_t * publisher)
eclipse_zenoh_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);

RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_destroy_publisher] %s", publisher->topic_name);

// OBTAIN ALLOCATOR ==========================================================
rcutils_allocator_t * allocator = &node->context->options.allocator;

Expand Down Expand Up @@ -254,8 +259,7 @@ rmw_publisher_get_actual_qos(const rmw_publisher_t * publisher, rmw_qos_profile_
{
(void)publisher;
(void)qos_profile;
// RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "rmw_publisher_get_actual_qos");
// return RMW_RET_ERROR;
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_publisher_get_actual_qos (STUB)");
return RMW_RET_OK;
}

Expand Down
17 changes: 8 additions & 9 deletions rmw_zenoh_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ rmw_create_service(
const char * service_name,
const rmw_qos_profile_t * qos_profile)
{
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "[rmw_create_service] %s", service_name);
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_create_service] %s", service_name);

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(node, nullptr);
Expand Down Expand Up @@ -233,7 +233,7 @@ rmw_create_service(
rmw_ret_t
rmw_destroy_service(rmw_node_t * node, rmw_service_t * service)
{
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "[rmw_destroy_service] %s", service->service_name);
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_destroy_service] %s", service->service_name);

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_INVALID_ARGUMENT);
Expand Down Expand Up @@ -279,7 +279,7 @@ rmw_take_request(
bool * taken)
{
*taken = false;
// RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "rmw_take_request");
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "rmw_take_request");

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(service, RMW_RET_INVALID_ARGUMENT);
Expand Down Expand Up @@ -314,7 +314,7 @@ rmw_take_request(
// This tells rcl that the check for a new message was done, but no messages have come in yet.
return RMW_RET_OK;
}
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "[rmw_take_request] Request found: %s", key.c_str());
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_take_request] Request found: %s", key.c_str());

auto request_bytes = service_data->zn_request_messages_[key];

Expand Down Expand Up @@ -349,7 +349,7 @@ rmw_take_request(
if (!service_data->request_type_support_->deserializeROSmessage(
deser, ros_request, service_data->request_type_support_impl_)
) {
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp", "COULD NOT DESERIALIZE REQUEST MESSAGE");
RMW_SET_ERROR_MSG("could not deserialize request message");
return RMW_RET_ERROR;
}

Expand All @@ -364,10 +364,9 @@ rmw_send_response(const rmw_service_t * service,
rmw_request_id_t * request_header, // In parameter
void * ros_response)
{
RCUTILS_LOG_INFO_NAMED("rmw_zenoh_cpp",
"[rmw_send_response] %s (%ld)",
service->service_name,
static_cast<rmw_service_data_t *>(service->data)->zn_response_topic_id_);
RCUTILS_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "[rmw_send_response] %s (%ld)",
service->service_name,
static_cast<rmw_service_data_t *>(service->data)->zn_response_topic_id_);

// ASSERTIONS ================================================================
RMW_CHECK_ARGUMENT_FOR_NULL(service, RMW_RET_INVALID_ARGUMENT);
Expand Down
Loading