rcl
master
C API providing common ROS client library functionality.
|
#include <rmw/names_and_types.h>
#include <rmw/get_topic_names_and_types.h>
#include "rcutils/types.h"
#include "rosidl_generator_c/service_type_support_struct.h"
#include "rcl/macros.h"
#include "rcl/client.h"
#include "rcl/node.h"
#include "rcl/visibility_control.h"
Go to the source code of this file.
Macros | |
#define | rcl_get_zero_initialized_names_and_types rmw_get_zero_initialized_names_and_types |
Typedefs | |
typedef rmw_names_and_types_t | rcl_names_and_types_t |
Functions | |
rcl_ret_t | rcl_get_topic_names_and_types (const rcl_node_t *node, rcl_allocator_t *allocator, bool no_demangle, rcl_names_and_types_t *topic_names_and_types) |
Return a list of topic names and their types. More... | |
rcl_ret_t | rcl_get_service_names_and_types (const rcl_node_t *node, rcl_allocator_t *allocator, rcl_names_and_types_t *service_names_and_types) |
Return a list of service names and their types. More... | |
rcl_ret_t | rcl_names_and_types_fini (rcl_names_and_types_t *names_and_types) |
Finalize a rcl_names_and_types_t object. More... | |
rcl_ret_t | rcl_get_node_names (const rcl_node_t *node, rcl_allocator_t allocator, rcutils_string_array_t *node_names) |
Return a list of available nodes in the ROS graph. More... | |
rcl_ret_t | rcl_count_publishers (const rcl_node_t *node, const char *topic_name, size_t *count) |
Return the number of publishers on a given topic. More... | |
rcl_ret_t | rcl_count_subscribers (const rcl_node_t *node, const char *topic_name, size_t *count) |
Return the number of subscriptions on a given topic. More... | |
rcl_ret_t | rcl_service_server_is_available (const rcl_node_t *node, const rcl_client_t *client, bool *is_available) |
Check if a service server is available for the given service client. More... | |
#define rcl_get_zero_initialized_names_and_types rmw_get_zero_initialized_names_and_types |
rcl_ret_t rcl_get_topic_names_and_types | ( | const rcl_node_t * | node, |
rcl_allocator_t * | allocator, | ||
bool | no_demangle, | ||
rcl_names_and_types_t * | topic_names_and_types | ||
) |
Return a list of topic names and their types.
This function returns a list of topic names in the ROS graph and their types.
The node parameter must not be NULL
, and must point to a valid node.
The topic_names_and_types parameter must be allocated and zero initialized. The topic_names_and_types is the output for this function, and contains allocated memory. Therefore, it should be passed to rcl_names_and_types_fini() when it is no longer needed. Failing to do so will result in leaked memory.
There may be some demangling that occurs when listing the topics from the middleware implementation. If the no_demangle argument is true, then this will be avoided and the topics will be returned as they appear to the middleware.
The returned names are not automatically remapped by this function. Attempting to create publishers or subscribers using names returned by this function may not result in the desired topic name being used depending on the remap rules in use.
Attribute | Adherence — |
---|---|
Allocates Memory | Yes |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Maybe [1] |
[1] implementation may need to protect the data structure with a lock
[in] | node | the handle to the node being used to query the ROS graph |
[in] | allocator | allocator to be used when allocating space for strings |
[in] | no_demangle | if true, list all topics without any demangling |
[out] | topic_names_and_types | list of topic names and their types |
RCL_RET_OK
if the query was successful, or RCL_RET_NODE_INVALID
if the node is invalid, or RCL_RET_INVALID_ARGUMENT
if any arguments are invalid, or RCL_RET_ERROR
if an unspecified error occurs. rcl_ret_t rcl_get_service_names_and_types | ( | const rcl_node_t * | node, |
rcl_allocator_t * | allocator, | ||
rcl_names_and_types_t * | service_names_and_types | ||
) |
Return a list of service names and their types.
This function returns a list of service names in the ROS graph and their types.
The node parameter must not be NULL
, and must point to a valid node.
The service_names_and_types parameter must be allocated and zero initialized. The service_names_and_types is the output for this function, and contains allocated memory. Therefore, it should be passed to rcl_names_and_types_fini() when it is no longer needed. Failing to do so will result in leaked memory.
The returned names are not automatically remapped by this function. Attempting to create clients or services using names returned by this function may not result in the desired service name being used depending on the remap rules in use.
Attribute | Adherence — |
---|---|
Allocates Memory | Yes |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Maybe [1] |
[1] implementation may need to protect the data structure with a lock
[in] | node | the handle to the node being used to query the ROS graph |
[in] | allocator | allocator to be used when allocating space for strings |
[out] | service_names_and_types | list of service names and their types |
RCL_RET_OK
if the query was successful, or RCL_RET_NODE_INVALID
if the node is invalid, or RCL_RET_INVALID_ARGUMENT
if any arguments are invalid, or RCL_RET_ERROR
if an unspecified error occurs. rcl_ret_t rcl_names_and_types_fini | ( | rcl_names_and_types_t * | names_and_types | ) |
Finalize a rcl_names_and_types_t object.
The object is populated when given to one of the rcl_get_*_names_and_types() functions. This function reclaims any resources allocated during population.
The names_and_types parameter must not be NULL
, and must point to an already allocated rcl_names_and_types_t struct that was previously passed to a successful rcl_get_*_names_and_types() function call.
Attribute | Adherence — |
---|---|
Allocates Memory | Yes |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Yes |
[in,out] | names_and_types | struct to be finalized |
RCL_RET_OK
if successful, or RCL_RET_INVALID_ARGUMENT
if any arguments are invalid, or RCL_RET_ERROR
if an unspecified error occurs. rcl_ret_t rcl_get_node_names | ( | const rcl_node_t * | node, |
rcl_allocator_t | allocator, | ||
rcutils_string_array_t * | node_names | ||
) |
Return a list of available nodes in the ROS graph.
This function returns a list of nodes in the ROS graph.
The node parameter must not be NULL
, and must point to a valid node.
The node_names parameter must be allocated and zero initialized. The node_names is the output for this function, and contains allocated memory. Note that entries in the array might contain NULL
value. Use rcutils_get_zero_initialized_string_array() for initializing an empty rcutils_string_array_t struct. This node_names struct should therefore be passed to rcutils_string_array_fini() when it is no longer needed. Failing to do so will result in leaked memory.
Example:
Attribute | Adherence — |
---|---|
Allocates Memory | Yes |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Maybe [1] |
[1] implementation may need to protect the data structure with a lock
[in] | node | the handle to the node being used to query the ROS graph |
[in] | allocator | used to control allocation and deallocation of names |
[out] | node_names | struct storing discovered node names. |
RCL_RET_OK
if the query was successful, or RCL_RET_ERROR
if an unspecified error occurs. rcl_ret_t rcl_count_publishers | ( | const rcl_node_t * | node, |
const char * | topic_name, | ||
size_t * | count | ||
) |
Return the number of publishers on a given topic.
This function returns the number of publishers on a given topic.
The node parameter must not be NULL
, and must point to a valid node.
The topic_name parameter must not be NULL
, and must not be an empty string. It should also follow the topic name rules.
The count parameter must not be NULL
, and must point to a valid bool. The count parameter is the output for this function and will be set.
In the event that error handling needs to allocate memory, this function will try to use the node's allocator.
The topic name is not automatically remapped by this function. If there is a publisher created with topic name foo
and remap rule foo:=bar
then calling this with topic_name
set to bar
will return a count of 1, and with topic_name
set to foo
will return a count of 0. /sa rcl_remap_topic_name()
Attribute | Adherence — |
---|---|
Allocates Memory | No |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Maybe [1] |
[1] implementation may need to protect the data structure with a lock
[in] | node | the handle to the node being used to query the ROS graph |
[in] | topic_name | the name of the topic in question |
[out] | count | number of publishers on the given topic |
RCL_RET_OK
if the query was successful, or RCL_RET_NODE_INVALID
if the node is invalid, or RCL_RET_INVALID_ARGUMENT
if any arguments are invalid, or RCL_RET_ERROR
if an unspecified error occurs. rcl_ret_t rcl_count_subscribers | ( | const rcl_node_t * | node, |
const char * | topic_name, | ||
size_t * | count | ||
) |
Return the number of subscriptions on a given topic.
This function returns the number of subscriptions on a given topic.
The node parameter must not be NULL
, and must point to a valid node.
The topic_name parameter must not be NULL
, and must not be an empty string. It should also follow the topic name rules.
The count parameter must not be NULL
, and must point to a valid bool. The count parameter is the output for this function and will be set.
In the event that error handling needs to allocate memory, this function will try to use the node's allocator.
The topic name is not automatically remapped by this function. If there is a subscriber created with topic name foo
and remap rule foo:=bar
then calling this with topic_name
set to bar
will return a count of 1, and with topic_name
set to foo
will return a count of 0. /sa rcl_remap_topic_name()
Attribute | Adherence — |
---|---|
Allocates Memory | No |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Maybe [1] |
[1] implementation may need to protect the data structure with a lock
[in] | node | the handle to the node being used to query the ROS graph |
[in] | topic_name | the name of the topic in question |
[out] | count | number of subscriptions on the given topic |
RCL_RET_OK
if the query was successful, or RCL_RET_NODE_INVALID
if the node is invalid, or RCL_RET_INVALID_ARGUMENT
if any arguments are invalid, or RCL_RET_ERROR
if an unspecified error occurs. rcl_ret_t rcl_service_server_is_available | ( | const rcl_node_t * | node, |
const rcl_client_t * | client, | ||
bool * | is_available | ||
) |
Check if a service server is available for the given service client.
This function will return true for is_available if there is a service server available for the given client.
The node parameter must not be NULL
, and must point to a valid node.
The client parameter must not be NULL
, and must point to a valid client.
The given client and node must match, i.e. the client must have been created using the given node.
The is_available parameter must not be NULL
, and must point a bool variable. The result of the check will be stored in the is_available parameter.
In the event that error handling needs to allocate memory, this function will try to use the node's allocator.
Attribute | Adherence — |
---|---|
Allocates Memory | Yes |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Maybe [1] |
[1] implementation may need to protect the data structure with a lock
[in] | node | the handle to the node being used to query the ROS graph |
[in] | client | the handle to the service client being queried |
[out] | is_available | set to true if there is a service server available, else false |
RCL_RET_OK
if the check was made successfully (regardless of the service readiness), or RCL_RET_NODE_INVALID
if the node is invalid, or RCL_RET_INVALID_ARGUMENT
if any arguments are invalid, or RCL_RET_ERROR
if an unspecified error occurs.