Refactor get topic names and types (#144)
* cleanup * refactor for no_demangle and service n&t * fixup convenience function * add missing null check
This commit is contained in:
parent
c37bfec072
commit
6c5f98ed4c
6 changed files with 166 additions and 79 deletions
|
@ -20,8 +20,8 @@ extern "C"
|
||||||
{
|
{
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include <rmw/rmw.h>
|
#include <rmw/names_and_types.h>
|
||||||
#include <rmw/types.h>
|
#include <rmw/get_topic_names_and_types.h>
|
||||||
|
|
||||||
#include "rcutils/types.h"
|
#include "rcutils/types.h"
|
||||||
|
|
||||||
|
@ -32,13 +32,9 @@ extern "C"
|
||||||
#include "rcl/node.h"
|
#include "rcl/node.h"
|
||||||
#include "rcl/visibility_control.h"
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
typedef rmw_topic_names_and_types_t rcl_topic_names_and_types_t;
|
typedef rmw_names_and_types_t rcl_names_and_types_t;
|
||||||
|
|
||||||
/// Return a rcl_topic_names_and_types_t struct with members initialized to `NULL`.
|
#define rcl_get_zero_initialized_names_and_types rmw_get_zero_initialized_names_and_types
|
||||||
RCL_PUBLIC
|
|
||||||
RCL_WARN_UNUSED
|
|
||||||
rcl_topic_names_and_types_t
|
|
||||||
rcl_get_zero_initialized_topic_names_and_types(void);
|
|
||||||
|
|
||||||
/// Return a list of topic names and their types.
|
/// Return a list of topic names and their types.
|
||||||
/**
|
/**
|
||||||
|
@ -49,7 +45,54 @@ rcl_get_zero_initialized_topic_names_and_types(void);
|
||||||
* The topic_names_and_types parameter must be allocated and zero initialized.
|
* 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
|
* The topic_names_and_types is the output for this function, and contains
|
||||||
* allocated memory.
|
* allocated memory.
|
||||||
* Therefore, it should be passed to rcl_destroy_topic_names_and_types() when
|
* 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.
|
||||||
|
*
|
||||||
|
* \see rmw_get_topic_names_and_types for more details on no_demangle
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Maybe [1]
|
||||||
|
* <i>[1] implementation may need to protect the data structure with a lock</i>
|
||||||
|
*
|
||||||
|
* \param[in] node the handle to the node being used to query the ROS graph
|
||||||
|
* \param[in] allocator allocator to be used when allocating space for strings
|
||||||
|
* \param[in] no_demangle if true, list all topics without any demangling
|
||||||
|
* \param[out] topic_names_and_types list of topic names and their types
|
||||||
|
* \return `RCL_RET_OK` if the query was successful, or
|
||||||
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
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 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.
|
* it is no longer needed.
|
||||||
* Failing to do so will result in leaked memory.
|
* Failing to do so will result in leaked memory.
|
||||||
*
|
*
|
||||||
|
@ -64,7 +107,7 @@ rcl_get_zero_initialized_topic_names_and_types(void);
|
||||||
*
|
*
|
||||||
* \param[in] node the handle to the node being used to query the ROS graph
|
* \param[in] node the handle to the node being used to query the ROS graph
|
||||||
* \param[in] allocator allocator to be used when allocating space for strings
|
* \param[in] allocator allocator to be used when allocating space for strings
|
||||||
* \param[out] topic_names_and_types list of topic names and their types
|
* \param[out] service_names_and_types list of service names and their types
|
||||||
* \return `RCL_RET_OK` if the query was successful, or
|
* \return `RCL_RET_OK` if the query was successful, or
|
||||||
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
@ -73,16 +116,20 @@ rcl_get_zero_initialized_topic_names_and_types(void);
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_get_topic_names_and_types(
|
rcl_get_service_names_and_types(
|
||||||
const rcl_node_t * node,
|
const rcl_node_t * node,
|
||||||
rcl_allocator_t allocator,
|
rcl_allocator_t * allocator,
|
||||||
rcl_topic_names_and_types_t * topic_names_and_types);
|
rcl_names_and_types_t * service_names_and_types);
|
||||||
|
|
||||||
/// Destroy a struct which was previously given to rcl_get_topic_names_and_types.
|
/// Finalize a rcl_names_and_types_t object.
|
||||||
/**
|
/**
|
||||||
* The topic_names_and_types parameter must not be `NULL`, and must point to an
|
* The object is populated when given to one of the rcl_get_*_names_and_types()
|
||||||
* already allocated rcl_topic_names_and_types_t struct that was previously
|
* functions.
|
||||||
* passed to a successful rcl_get_topic_names_and_types() call.
|
* 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.
|
||||||
*
|
*
|
||||||
* <hr>
|
* <hr>
|
||||||
* Attribute | Adherence
|
* Attribute | Adherence
|
||||||
|
@ -92,7 +139,7 @@ rcl_get_topic_names_and_types(
|
||||||
* Uses Atomics | No
|
* Uses Atomics | No
|
||||||
* Lock-Free | Yes
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] topic_names_and_types struct to be destroyed
|
* \param[inout] names_and_types struct to be finalized
|
||||||
* \return `RCL_RET_OK` if successful, or
|
* \return `RCL_RET_OK` if successful, or
|
||||||
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
|
@ -100,8 +147,7 @@ rcl_get_topic_names_and_types(
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_destroy_topic_names_and_types(
|
rcl_names_and_types_fini(rcl_names_and_types_t * names_and_types);
|
||||||
rcl_topic_names_and_types_t * topic_names_and_types);
|
|
||||||
|
|
||||||
/// Return a list of available nodes in the ROS graph.
|
/// Return a list of available nodes in the ROS graph.
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -52,6 +52,21 @@ rcl_impl_getenv(const char * env_name, const char ** env_value)
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_convert_rmw_ret_to_rcl_ret(rmw_ret_t rmw_ret)
|
||||||
|
{
|
||||||
|
switch (rmw_ret) {
|
||||||
|
case RMW_RET_OK:
|
||||||
|
return RCL_RET_OK;
|
||||||
|
case RMW_RET_INVALID_ARGUMENT:
|
||||||
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
|
case RMW_RET_BAD_ALLOC:
|
||||||
|
return RCL_RET_BAD_ALLOC;
|
||||||
|
default:
|
||||||
|
return RCL_RET_ERROR;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
#if __cplusplus
|
#if __cplusplus
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -54,6 +54,10 @@ extern "C"
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_impl_getenv(const char * env_name, const char ** env_value);
|
rcl_impl_getenv(const char * env_name, const char ** env_value);
|
||||||
|
|
||||||
|
/// Convenience function for converting common rmw_ret_t return codes to rcl.
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_convert_rmw_ret_to_rcl_ret(rmw_ret_t rmw_ret);
|
||||||
|
|
||||||
#if __cplusplus
|
#if __cplusplus
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -17,55 +17,77 @@ extern "C"
|
||||||
{
|
{
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "rcutils/types.h"
|
|
||||||
|
|
||||||
#include "rcl/graph.h"
|
#include "rcl/graph.h"
|
||||||
|
|
||||||
#include "./common.h"
|
#include <rcutils/allocator.h>
|
||||||
|
#include <rcutils/types.h>
|
||||||
|
#include <rmw/get_service_names_and_types.h>
|
||||||
|
#include <rmw/get_topic_names_and_types.h>
|
||||||
|
#include <rmw/names_and_types.h>
|
||||||
|
#include <rmw/rmw.h>
|
||||||
|
|
||||||
rcl_topic_names_and_types_t
|
#include "./common.h"
|
||||||
rcl_get_zero_initialized_topic_names_and_types(void)
|
|
||||||
{
|
|
||||||
const rcl_topic_names_and_types_t null_topic_names_and_types = {0, NULL, NULL};
|
|
||||||
return null_topic_names_and_types;
|
|
||||||
}
|
|
||||||
|
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_get_topic_names_and_types(
|
rcl_get_topic_names_and_types(
|
||||||
const rcl_node_t * node,
|
const rcl_node_t * node,
|
||||||
rcl_allocator_t allocator,
|
rcl_allocator_t * allocator,
|
||||||
rcl_topic_names_and_types_t * topic_names_and_types)
|
bool no_demangle,
|
||||||
|
rcl_names_and_types_t * topic_names_and_types)
|
||||||
{
|
{
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, allocator);
|
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator())
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, *allocator)
|
||||||
if (!rcl_node_is_valid(node)) {
|
if (!rcl_node_is_valid(node)) {
|
||||||
return RCL_RET_NODE_INVALID;
|
return RCL_RET_NODE_INVALID;
|
||||||
}
|
}
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RCL_RET_INVALID_ARGUMENT, allocator);
|
RCL_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RCL_RET_INVALID_ARGUMENT, *allocator)
|
||||||
if (topic_names_and_types->topic_count != 0) {
|
rmw_ret_t rmw_ret;
|
||||||
RCL_SET_ERROR_MSG("topic count is not zero", allocator);
|
rmw_ret = rmw_names_and_types_check_zero(topic_names_and_types);
|
||||||
return RCL_RET_INVALID_ARGUMENT;
|
if (rmw_ret != RMW_RET_OK) {
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
}
|
}
|
||||||
if (topic_names_and_types->topic_names) {
|
rcutils_allocator_t rcutils_allocator = *allocator;
|
||||||
RCL_SET_ERROR_MSG("topic names is not null", allocator);
|
rmw_ret = rmw_get_topic_names_and_types(
|
||||||
return RCL_RET_INVALID_ARGUMENT;
|
|
||||||
}
|
|
||||||
if (topic_names_and_types->type_names) {
|
|
||||||
RCL_SET_ERROR_MSG("type names is not null", allocator);
|
|
||||||
return RCL_RET_INVALID_ARGUMENT;
|
|
||||||
}
|
|
||||||
return rmw_get_topic_names_and_types(
|
|
||||||
rcl_node_get_rmw_handle(node),
|
rcl_node_get_rmw_handle(node),
|
||||||
|
&rcutils_allocator,
|
||||||
|
no_demangle,
|
||||||
topic_names_and_types
|
topic_names_and_types
|
||||||
);
|
);
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
}
|
}
|
||||||
|
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_destroy_topic_names_and_types(
|
rcl_get_service_names_and_types(
|
||||||
rcl_topic_names_and_types_t * topic_names_and_types)
|
const rcl_node_t * node,
|
||||||
|
rcl_allocator_t * allocator,
|
||||||
|
rcl_names_and_types_t * service_names_and_types)
|
||||||
|
{
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, *allocator);
|
||||||
|
if (!rcl_node_is_valid(node)) {
|
||||||
|
return RCL_RET_NODE_INVALID;
|
||||||
|
}
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(service_names_and_types, RCL_RET_INVALID_ARGUMENT, *allocator);
|
||||||
|
rmw_ret_t rmw_ret;
|
||||||
|
rmw_ret = rmw_names_and_types_check_zero(service_names_and_types);
|
||||||
|
if (rmw_ret != RMW_RET_OK) {
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
|
}
|
||||||
|
rcutils_allocator_t rcutils_allocator = *allocator;
|
||||||
|
rmw_ret = rmw_get_service_names_and_types(
|
||||||
|
rcl_node_get_rmw_handle(node),
|
||||||
|
&rcutils_allocator,
|
||||||
|
service_names_and_types
|
||||||
|
);
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
|
}
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_names_and_types_fini(rcl_names_and_types_t * topic_names_and_types)
|
||||||
{
|
{
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(
|
RCL_CHECK_ARGUMENT_FOR_NULL(
|
||||||
topic_names_and_types, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
|
topic_names_and_types, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
|
||||||
return rmw_destroy_topic_names_and_types(topic_names_and_types);
|
rmw_ret_t rmw_ret = rmw_names_and_types_fini(topic_names_and_types);
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
}
|
}
|
||||||
|
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
|
@ -87,9 +109,10 @@ rcl_get_node_names(
|
||||||
RCL_SET_ERROR_MSG("node_names is not null", allocator);
|
RCL_SET_ERROR_MSG("node_names is not null", allocator);
|
||||||
return RCL_RET_INVALID_ARGUMENT;
|
return RCL_RET_INVALID_ARGUMENT;
|
||||||
}
|
}
|
||||||
return rmw_get_node_names(
|
rmw_ret_t rmw_ret = rmw_get_node_names(
|
||||||
rcl_node_get_rmw_handle(node),
|
rcl_node_get_rmw_handle(node),
|
||||||
node_names);
|
node_names);
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
}
|
}
|
||||||
|
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
|
@ -108,7 +131,8 @@ rcl_count_publishers(
|
||||||
}
|
}
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(count, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
RCL_CHECK_ARGUMENT_FOR_NULL(count, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
||||||
return rmw_count_publishers(rcl_node_get_rmw_handle(node), topic_name, count);
|
rmw_ret_t rmw_ret = rmw_count_publishers(rcl_node_get_rmw_handle(node), topic_name, count);
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
}
|
}
|
||||||
|
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
|
@ -127,7 +151,8 @@ rcl_count_subscribers(
|
||||||
}
|
}
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(count, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
RCL_CHECK_ARGUMENT_FOR_NULL(count, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
||||||
return rmw_count_subscribers(rcl_node_get_rmw_handle(node), topic_name, count);
|
rmw_ret_t rmw_ret = rmw_count_subscribers(rcl_node_get_rmw_handle(node), topic_name, count);
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
}
|
}
|
||||||
|
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
|
@ -146,11 +171,12 @@ rcl_service_server_is_available(
|
||||||
}
|
}
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(is_available, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
RCL_CHECK_ARGUMENT_FOR_NULL(is_available, RCL_RET_INVALID_ARGUMENT, node_options->allocator);
|
||||||
return rmw_service_server_is_available(
|
rmw_ret_t rmw_ret = rmw_service_server_is_available(
|
||||||
rcl_node_get_rmw_handle(node),
|
rcl_node_get_rmw_handle(node),
|
||||||
rcl_client_get_rmw_handle(client),
|
rcl_client_get_rmw_handle(client),
|
||||||
is_available
|
is_available
|
||||||
);
|
);
|
||||||
|
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if __cplusplus
|
#if __cplusplus
|
||||||
|
|
|
@ -92,7 +92,7 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names)
|
||||||
EXPECT_EQ(0, strcmp(node1_name, node_names.data[0]));
|
EXPECT_EQ(0, strcmp(node1_name, node_names.data[0]));
|
||||||
EXPECT_EQ(0, strcmp(node2_name, node_names.data[1]));
|
EXPECT_EQ(0, strcmp(node2_name, node_names.data[1]));
|
||||||
|
|
||||||
ret = rcutils_string_array_fini(&node_names, &node1_options.allocator);
|
ret = rcutils_string_array_fini(&node_names);
|
||||||
ASSERT_EQ(RCUTILS_RET_OK, ret);
|
ASSERT_EQ(RCUTILS_RET_OK, ret);
|
||||||
|
|
||||||
ret = rcl_node_fini(node1_ptr);
|
ret = rcl_node_fini(node1_ptr);
|
||||||
|
|
|
@ -123,30 +123,35 @@ TEST_F(
|
||||||
) {
|
) {
|
||||||
stop_memory_checking();
|
stop_memory_checking();
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_topic_names_and_types_t tnat {};
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
|
rcl_names_and_types_t tnat {};
|
||||||
rcl_node_t zero_node = rcl_get_zero_initialized_node();
|
rcl_node_t zero_node = rcl_get_zero_initialized_node();
|
||||||
// invalid node
|
// invalid node
|
||||||
ret = rcl_get_topic_names_and_types(nullptr, rcl_get_default_allocator(), &tnat);
|
ret = rcl_get_topic_names_and_types(nullptr, &allocator, false, &tnat);
|
||||||
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe();
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
ret = rcl_get_topic_names_and_types(&zero_node, rcl_get_default_allocator(), &tnat);
|
ret = rcl_get_topic_names_and_types(&zero_node, &allocator, false, &tnat);
|
||||||
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe();
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
ret = rcl_get_topic_names_and_types(this->old_node_ptr, rcl_get_default_allocator(), &tnat);
|
ret = rcl_get_topic_names_and_types(this->old_node_ptr, &allocator, false, &tnat);
|
||||||
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe();
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
|
// invalid allocator
|
||||||
|
ret = rcl_get_topic_names_and_types(this->node_ptr, nullptr, false, &tnat);
|
||||||
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe();
|
||||||
|
rcl_reset_error();
|
||||||
// invalid topic_names_and_types
|
// invalid topic_names_and_types
|
||||||
ret = rcl_get_topic_names_and_types(this->node_ptr, rcl_get_default_allocator(), nullptr);
|
ret = rcl_get_topic_names_and_types(this->node_ptr, &allocator, false, nullptr);
|
||||||
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe();
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
// invalid argument to rcl_destroy_topic_names_and_types
|
// invalid argument to rcl_destroy_topic_names_and_types
|
||||||
ret = rcl_destroy_topic_names_and_types(nullptr);
|
ret = rcl_names_and_types_fini(nullptr);
|
||||||
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe();
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
// valid calls
|
// valid calls
|
||||||
ret = rcl_get_topic_names_and_types(this->node_ptr, rcl_get_default_allocator(), &tnat);
|
ret = rcl_get_topic_names_and_types(this->node_ptr, &allocator, false, &tnat);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
ret = rcl_destroy_topic_names_and_types(&tnat);
|
ret = rcl_names_and_types_fini(&tnat);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -246,8 +251,9 @@ check_graph_state(
|
||||||
size_t publisher_count = 0;
|
size_t publisher_count = 0;
|
||||||
size_t subscriber_count = 0;
|
size_t subscriber_count = 0;
|
||||||
bool is_in_tnat = false;
|
bool is_in_tnat = false;
|
||||||
rcl_topic_names_and_types_t tnat {};
|
rcl_names_and_types_t tnat {};
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
for (size_t i = 0; i < number_of_tries; ++i) {
|
for (size_t i = 0; i < number_of_tries; ++i) {
|
||||||
ret = rcl_count_publishers(node_ptr, topic_name.c_str(), &publisher_count);
|
ret = rcl_count_publishers(node_ptr, topic_name.c_str(), &publisher_count);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
|
@ -257,19 +263,19 @@ check_graph_state(
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
|
|
||||||
tnat = rcl_get_zero_initialized_topic_names_and_types();
|
tnat = rcl_get_zero_initialized_names_and_types();
|
||||||
ret = rcl_get_topic_names_and_types(node_ptr, rcl_get_default_allocator(), &tnat);
|
ret = rcl_get_topic_names_and_types(node_ptr, &allocator, false, &tnat);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
is_in_tnat = false;
|
is_in_tnat = false;
|
||||||
for (size_t i = 0; RCL_RET_OK == ret && i < tnat.topic_count; ++i) {
|
for (size_t i = 0; RCL_RET_OK == ret && i < tnat.names.size; ++i) {
|
||||||
if (topic_name == tnat.topic_names[i]) {
|
if (topic_name == std::string(tnat.names.data[i])) {
|
||||||
ASSERT_FALSE(is_in_tnat) << "duplicates in the tnat"; // Found it more than once!
|
ASSERT_FALSE(is_in_tnat) << "duplicates in the tnat"; // Found it more than once!
|
||||||
is_in_tnat = true;
|
is_in_tnat = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (RCL_RET_OK == ret) {
|
if (RCL_RET_OK == ret) {
|
||||||
ret = rcl_destroy_topic_names_and_types(&tnat);
|
ret = rcl_names_and_types_fini(&tnat);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
}
|
}
|
||||||
|
@ -288,16 +294,6 @@ check_graph_state(
|
||||||
{
|
{
|
||||||
printf(" state correct!\n");
|
printf(" state correct!\n");
|
||||||
break;
|
break;
|
||||||
} else {
|
|
||||||
if (expected_publisher_count != publisher_count) {
|
|
||||||
printf(" pub count incorrect!\n");
|
|
||||||
}
|
|
||||||
if (expected_subscriber_count != subscriber_count) {
|
|
||||||
printf(" sub count incorrect!\n");
|
|
||||||
}
|
|
||||||
if (expected_in_tnat != is_in_tnat) {
|
|
||||||
printf(" in tnat incorrect!\n");
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
// Wait for graph change before trying again.
|
// Wait for graph change before trying again.
|
||||||
if ((i + 1) == number_of_tries) {
|
if ((i + 1) == number_of_tries) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue