use string_array_t from c_utilities package (#118)

* use c_utilities package

* add doc for get_node_names

* fix typo

* fixup docs

* fix tests to handle return value of destroy function
This commit is contained in:
Karsten Knese 2017-04-14 16:18:23 -07:00 committed by GitHub
parent a78c18b58b
commit 08d9763ce7
5 changed files with 60 additions and 69 deletions

View file

@ -3,6 +3,7 @@ cmake_minimum_required(VERSION 3.5)
project(rcl)
find_package(ament_cmake_ros REQUIRED)
find_package(c_utilities REQUIRED)
find_package(rcl_interfaces REQUIRED)
find_package(rmw REQUIRED)
find_package(rmw_implementation REQUIRED)
@ -34,6 +35,7 @@ set(${PROJECT_NAME}_sources
add_library(${PROJECT_NAME} ${${PROJECT_NAME}_sources})
ament_target_dependencies(${PROJECT_NAME}
"c_utilities"
"rcl_interfaces"
"rmw"
"rmw_implementation"

View file

@ -23,6 +23,8 @@ extern "C"
#include <rmw/rmw.h>
#include <rmw/types.h>
#include "c_utilities/types.h"
#include "rosidl_generator_c/service_type_support.h"
#include "rcl/macros.h"
@ -31,8 +33,6 @@ extern "C"
#include "rcl/visibility_control.h"
typedef rmw_topic_names_and_types_t rcl_topic_names_and_types_t;
typedef rmw_string_array_t rcl_string_array_t;
/// Return a rcl_topic_names_and_types_t struct with members initialized to `NULL`.
RCL_PUBLIC
@ -40,12 +40,6 @@ RCL_WARN_UNUSED
rcl_topic_names_and_types_t
rcl_get_zero_initialized_topic_names_and_types(void);
/// Return a rcl_node_names_t struct with members initialized to `NULL`.
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_string_array_t
rcl_get_zero_initialized_string_array(void);
/// Return a list of topic names and their types.
/**
* This function returns a list of topic names in the ROS graph and their types.
@ -107,18 +101,57 @@ rcl_ret_t
rcl_destroy_topic_names_and_types(
rcl_topic_names_and_types_t * topic_names_and_types);
/// 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.
* Use utilities_get_zero_initialized_string_array() for initializing an empty
* utilities_string_array_t struct.
* This node_names struct should therefore be passed to utilities_string_array_fini()
* when it is no longer needed.
* Failing to do so will result in leaked memory.
*
* Example:
*
* ```c
* utilities_string_array_t node_names =
* utilities_get_zero_initialized_string_array();
* rcl_ret_t ret = rcl_get_node_names(node, &node_names);
* if (ret != RCL_RET_OK) {
* // ... error handling
* }
* // ... use the node_names struct, and when done:
* utilitiest_ret_t utilities_ret = utilities_string_array_fini(&node_names);
* if (utilities_ret != UTILITIES_RET_OK) {
* // ... error handling
* }
* ```
*
* <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[out] node_names struct storing discovered node names.
* \return `RCL_RET_OK` if the query was successful, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_get_node_names(
const rcl_node_t * node,
rcl_string_array_t * node_names);
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_destroy_node_names(
rcl_string_array_t * node_names);
utilities_string_array_t * node_names);
/// Return the number of publishers on a given topic.
/**

View file

@ -17,6 +17,8 @@ extern "C"
{
#endif
#include "c_utilities/types.h"
#include "rcl/graph.h"
#include "./common.h"
@ -28,13 +30,6 @@ rcl_get_zero_initialized_topic_names_and_types(void)
return null_topic_names_and_types;
}
rcl_string_array_t
rcl_get_zero_initialized_string_array(void)
{
const rcl_string_array_t null_string_array = {0, NULL};
return null_string_array;
}
rcl_ret_t
rcl_get_topic_names_and_types(
const rcl_node_t * node,
@ -74,7 +69,7 @@ rcl_destroy_topic_names_and_types(
rcl_ret_t
rcl_get_node_names(
const rcl_node_t * node,
rcl_string_array_t * node_names)
utilities_string_array_t * node_names)
{
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node)) {
@ -94,14 +89,6 @@ rcl_get_node_names(
node_names);
}
rcl_ret_t
rcl_destroy_node_names(
rcl_string_array_t * node_names)
{
RCL_CHECK_ARGUMENT_FOR_NULL(node_names, RCL_RET_INVALID_ARGUMENT);
return rmw_destroy_node_names(node_names);
}
rcl_ret_t
rcl_count_publishers(
const rcl_node_t * node,

View file

@ -17,6 +17,8 @@
#include <chrono>
#include <thread>
#include "c_utilities/types.h"
#include "rcl/graph.h"
#include "rcl/rcl.h"
#include "rmw/rmw.h"
@ -75,14 +77,17 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names)
std::this_thread::sleep_for(1s);
rcl_string_array_t node_names = rcl_get_zero_initialized_string_array();
utilities_string_array_t node_names = utilities_get_zero_initialized_string_array();
ret = rcl_get_node_names(node1_ptr, &node_names);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
ASSERT_EQ(UTILITIES_RET_OK, ret) << rcl_get_error_string_safe();
EXPECT_EQ(size_t(2), node_names.size);
EXPECT_EQ(0, strcmp(node1_name, node_names.data[0]));
EXPECT_EQ(0, strcmp(node2_name, node_names.data[1]));
ret = utilities_string_array_fini(&node_names);
ASSERT_EQ(UTILITIES_RET_OK, ret);
ret = rcl_node_fini(node1_ptr);
delete node1_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();

View file

@ -150,42 +150,6 @@ TEST_F(
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
}
/* Test the rcl_get_topic_names_and_types and rcl_destroy_topic_names_and_types functions.
*
* This does not test content of the rcl_topic_names_and_types_t structure.
*/
TEST_F(
CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION),
test_rcl_get_and_destroy_node_names) {
stop_memory_checking();
rcl_ret_t ret;
rcl_string_array_t node_names {};
rcl_node_t zero_node = rcl_get_zero_initialized_node();
// invalid node
ret = rcl_get_node_names(nullptr, &node_names);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe();
rcl_reset_error();
ret = rcl_get_node_names(&zero_node, &node_names);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe();
rcl_reset_error();
ret = rcl_get_node_names(this->old_node_ptr, &node_names);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe();
rcl_reset_error();
// invalid topic_names_and_types
ret = rcl_get_node_names(this->node_ptr, nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe();
rcl_reset_error();
// invalid argument to rcl_destroy_topic_names_and_types
ret = rcl_destroy_node_names(nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe();
rcl_reset_error();
// valid calls
ret = rcl_get_node_names(this->node_ptr, &node_names);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
ret = rcl_destroy_node_names(&node_names);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
}
/* Test the rcl_count_publishers function.
*
* This does not test content the response.