Skip to content

Commit

Permalink
Update some comments.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Feb 2, 2023
1 parent 0eba9a3 commit 07fb3ba
Show file tree
Hide file tree
Showing 6 changed files with 95 additions and 39 deletions.
42 changes: 35 additions & 7 deletions rcl/include/rcl/client.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,16 @@ extern "C"

#include "rosidl_runtime_c/service_type_support_struct.h"

#include "rcl/allocator.h"
#include "rcl/event_callback.h"
#include "rcl/macros.h"
#include "rcl/node.h"
#include "rcl/publisher.h"
#include "rcl/time.h"
#include "rcl/visibility_control.h"

#include "rmw/types.h"

/// Internal rcl client implementation struct.
typedef struct rcl_client_impl_s rcl_client_impl_t;

Expand Down Expand Up @@ -202,10 +205,10 @@ rcl_client_fini(rcl_client_t * client, rcl_node_t * node);
* The defaults are:
*
* - qos = rmw_qos_profile_services_default
* - event_publisher_qos = rcl_publisher_get_default_options()
* - event_publisher_options = rcl_publisher_get_default_options()
* - allocator = rcl_get_default_allocator()
* - clock = NULL
* - enable_service_introspection = False
* - clock = NULL
*/
RCL_PUBLIC
RCL_WARN_UNUSED
Expand Down Expand Up @@ -504,9 +507,9 @@ rcl_client_set_on_new_response_callback(
rcl_event_callback_t callback,
const void * user_data);

/// Configures service introspection features for the client
/*
* This function is a thin wrapper around rcl_service_introspection_enable
/// Configures service introspection features for the client.
/**
* Enables or disables service introspection features for this client.
*
* <hr>
* Attribute | Adherence
Expand All @@ -516,9 +519,15 @@ rcl_client_set_on_new_response_callback(
* Uses Atomics | Maybe [1]
* Lock-Free | Maybe [1]
* <i>[1] rmw implementation defined</i>
* \param[in] client The client on which to enable service introspection
*
* \param[in] client The client on which to configure service introspection
* \param[in] node The node for which the service event publisher is to be associated to
* \param[in] enable Whether to enable or disable service introspection for the client.
* \return `RCL_RET_ERROR` if the event publisher is invalid, or
* \return `RCL_RET_NODE_INVALID` if the given node is invalid, or
* \return `RCL_RET_INVALID_ARGUMENT` if the client or node structure is invalid,
* \return `RCL_RET_BAD_ALLOC` if a memory allocation failed, or
* \return `RCL_RET_OK` if the call was successful
*/
RCL_PUBLIC
RCL_WARN_UNUSED
Expand All @@ -528,8 +537,27 @@ rcl_service_introspection_configure_client_service_events(
rcl_node_t * node,
bool enable);

/// Configures whether service introspection messages contain only metadata or content.
/**
* Enables or disables whether service introspection messages contain just the metadata
* about the transaction, or also contains the content.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] client The client on which to configure content
* \param[in] enable Whether to enable or disable service introspection content
* \return `RCL_RET_INVALID_ARGUMENT` if the client structure is invalid,
* \return `RCL_RET_OK` if the call was successful
*/
RCL_PUBLIC
void
RCL_WARN_UNUSED
rcl_ret_t
rcl_service_introspection_configure_client_service_event_message_payload(
rcl_client_t * client,
bool enable);
Expand Down
32 changes: 23 additions & 9 deletions rcl/include/rcl/service.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,16 @@ extern "C"

#include "rosidl_runtime_c/service_type_support_struct.h"

#include "rcl/allocator.h"
#include "rcl/event_callback.h"
#include "rcl/macros.h"
#include "rcl/node.h"
#include "rcl/time.h"
#include "rcl/publisher.h"
#include "rcl/time.h"
#include "rcl/visibility_control.h"

#include "rmw/types.h"

/// Internal rcl implementation struct.
typedef struct rcl_service_impl_s rcl_service_impl_t;

Expand Down Expand Up @@ -113,7 +116,7 @@ rcl_get_zero_initialized_service(void);
*
* The options struct allows the user to set the quality of service settings as
* well as a custom allocator which is used when initializing/finalizing the
* server to allocate space for incidentals, e.g. the service name string.
* service to allocate space for incidentals, e.g. the service name string.
*
* Expected usage (for C services):
*
Expand Down Expand Up @@ -205,10 +208,10 @@ rcl_service_fini(rcl_service_t * service, rcl_node_t * node);
* The defaults are:
*
* - qos = rmw_qos_profile_services_default
* - event_publisher_qos = rcl_publisher_get_default_options()
* - event_publisher_options = rcl_publisher_get_default_options()
* - allocator = rcl_get_default_allocator()
* - clock = NULL
* - enable_service_introspection = False
* - clock = NULL
*/
RCL_PUBLIC
RCL_WARN_UNUSED
Expand Down Expand Up @@ -292,7 +295,7 @@ rcl_take_request(
rmw_request_id_t * request_header,
void * ros_request);

/// Send a ROS response to a server using a service.
/// Send a ROS response to a client using a service.
/**
* It is the job of the caller to ensure that the type of the `ros_response`
* parameter and the type associate with the service (via the type support)
Expand Down Expand Up @@ -536,8 +539,8 @@ rcl_service_set_on_new_request_callback(
const void * user_data);

/// Configure service introspection features for the service
/*
* This function is a thin wrapper around rcl_service_introspection_enable
/**
* Enables or disables service introspection features for this service.
*
* <hr>
* Attribute | Adherence
Expand All @@ -546,9 +549,16 @@ rcl_service_set_on_new_request_callback(
* Thread-Safe | No
* Uses Atomics | Maybe [1]
* Lock-Free | Maybe [1]
* <i>[1] rmw implementation defined</i>
*
* \param[in] server The server on which to enable service introspection
* \param[in] node The node for which the service event publisher is to be associated to
* \param[in] enable Whether to enable or disable service introspection
* \return `RCL_RET_ERROR` if the event publisher is invalid, or
* \return `RCL_RET_NODE_INVALID` if the given node is invalid, or
* \return `RCL_RET_INVALID_ARGUMENT` if the client or node structure is invalid,
* \return `RCL_RET_BAD_ALLOC` if a memory allocation failed, or
* \return `RCL_RET_OK` if the call was successful
*/
RCL_PUBLIC
RCL_WARN_UNUSED
Expand All @@ -559,19 +569,23 @@ rcl_service_introspection_configure_server_service_events(
bool enable);

/// Configure if the payload (server response) is included in service event messages.
/*
/**
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] server The server on which to enable/disable payload for service event messages.
* \param[in] enable Whether to enable or disable including the payload in the event message.
* \return `RCL_RET_INVALID_ARGUMENT` if the service structure is invalid,
* \return `RCL_RET_OK` if the call was successful
*/
RCL_PUBLIC
void
RCL_WARN_UNUSED
rcl_ret_t
rcl_service_introspection_configure_server_service_event_message_payload(
rcl_service_t * service,
bool enable);
Expand Down
20 changes: 15 additions & 5 deletions rcl/src/rcl/client.c
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,13 @@ extern "C"
#include "rcl/error_handling.h"
#include "rcl/node.h"
#include "rcl/publisher.h"
#include "rmw/error_handling.h"
#include "rmw/rmw.h"
#include "rcutils/logging_macros.h"
#include "rcutils/macros.h"
#include "tracetools/tracetools.h"
#include "rcutils/stdatomic_helper.h"
#include "rmw/error_handling.h"
#include "rmw/rmw.h"
#include "service_msgs/msg/service_event_info.h"
#include "tracetools/tracetools.h"

#include "./common.h"
#include "./client_impl.h"
Expand Down Expand Up @@ -235,8 +236,8 @@ rcl_client_get_default_options()
default_options.qos = rmw_qos_profile_services_default;
default_options.event_publisher_options = rcl_publisher_get_default_options();
default_options.allocator = rcl_get_default_allocator();
default_options.clock = NULL;
default_options.enable_service_introspection = false;
default_options.clock = NULL;
return default_options;
}

Expand Down Expand Up @@ -423,18 +424,27 @@ rcl_service_introspection_configure_client_service_events(
rcl_node_t * node,
bool enable)
{
RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(client->impl, RCL_RET_INVALID_ARGUMENT);

if (enable) {
return rcl_service_introspection_enable(client->impl->service_event_publisher, node);
}
return rcl_service_introspection_disable(client->impl->service_event_publisher, node);
}

void
rcl_ret_t
rcl_service_introspection_configure_client_service_event_message_payload(
rcl_client_t * client,
bool enable)
{
RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(client->impl, RCL_RET_INVALID_ARGUMENT);

client->impl->service_event_publisher->impl->options._content_enabled = enable;

return RCL_RET_OK;
}

#ifdef __cplusplus
Expand Down
4 changes: 2 additions & 2 deletions rcl/src/rcl/client_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,10 @@
#ifndef RCL__CLIENT_IMPL_H_
#define RCL__CLIENT_IMPL_H_


#include "rcl/client.h"

#include "rcutils/stdatomic_helper.h"
#include "rmw/types.h"

#include "./service_event_publisher.h"

struct rcl_client_impl_s
Expand Down
30 changes: 16 additions & 14 deletions rcl/src/rcl/service.c
Original file line number Diff line number Diff line change
Expand Up @@ -20,19 +20,16 @@ extern "C"
#include <stdio.h>
#include <string.h>

#include "rcl/error_handling.h"
#include "rcl/graph.h"
#include "rcl/node.h"
#include "rcl/publisher.h"

#include "rcl/time.h"
#include "rcl/types.h"
#include "rcl/error_handling.h"
#include "rcl/node.h"
#include "rcl/graph.h"

#include "rmw/error_handling.h"
#include "rmw/rmw.h"

#include "rcutils/logging_macros.h"
#include "rcutils/macros.h"
#include "rmw/error_handling.h"
#include "rmw/rmw.h"

#include "tracetools/tracetools.h"

Expand Down Expand Up @@ -245,10 +242,6 @@ rcl_service_fini(rcl_service_t * service, rcl_node_t * node)

allocator.deallocate(service->impl, allocator.state);
service->impl = NULL;
if (ret != RCL_RET_OK) {
RCL_SET_ERROR_MSG(rcl_get_error_string().str);
result = RCL_RET_ERROR;
}
}
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Service finalized");
return result;
Expand All @@ -263,8 +256,8 @@ rcl_service_get_default_options()
default_options.qos = rmw_qos_profile_services_default;
default_options.event_publisher_options = rcl_publisher_get_default_options();
default_options.allocator = rcl_get_default_allocator();
default_options.clock = NULL;
default_options.enable_service_introspection = false;
default_options.clock = NULL;
return default_options;
}

Expand Down Expand Up @@ -447,18 +440,27 @@ rcl_service_introspection_configure_server_service_events(
rcl_node_t * node,
bool enable)
{
RCL_CHECK_ARGUMENT_FOR_NULL(service, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(service->impl, RCL_RET_INVALID_ARGUMENT);

if (enable) {
return rcl_service_introspection_enable(service->impl->service_event_publisher, node);
}
return rcl_service_introspection_disable(service->impl->service_event_publisher, node);
}

void
rcl_ret_t
rcl_service_introspection_configure_server_service_event_message_payload(
rcl_service_t * service,
bool enable)
{
RCL_CHECK_ARGUMENT_FOR_NULL(service, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(service->impl, RCL_RET_INVALID_ARGUMENT);

service->impl->service_event_publisher->impl->options._content_enabled = enable;

return RCL_RET_OK;
}

#ifdef __cplusplus
Expand Down
6 changes: 4 additions & 2 deletions rcl_action/src/rcl_action/action_client.c
Original file line number Diff line number Diff line change
Expand Up @@ -116,9 +116,11 @@ _rcl_action_client_fini_impl(
Type ## _event_publisher_options.qos = options->service_event_qos; \
Type ## _event_publisher_options.allocator = allocator; \
rcl_client_options_t Type ## _service_client_options = { \
.qos = options->Type ## _service_qos, .allocator = allocator, .clock = clock, \
.qos = options->Type ## _service_qos, \
.event_publisher_options = Type ## _event_publisher_options, \
.enable_service_introspection = rcl_node_get_options(node)->enable_service_introspection \
.allocator = allocator, \
.enable_service_introspection = rcl_node_get_options(node)->enable_service_introspection, \
.clock = clock \
}; \
action_client->impl->Type ## _client = rcl_get_zero_initialized_client(); \
ret = rcl_client_init( \
Expand Down

0 comments on commit 07fb3ba

Please sign in to comment.