diff --git a/rcl_action/CMakeLists.txt b/rcl_action/CMakeLists.txt
index f16868b54..ffb1fa65b 100644
--- a/rcl_action/CMakeLists.txt
+++ b/rcl_action/CMakeLists.txt
@@ -36,6 +36,7 @@ set(rcl_action_sources
src/${PROJECT_NAME}/action_server.c
src/${PROJECT_NAME}/goal_handle.c
src/${PROJECT_NAME}/goal_state_machine.c
+ src/${PROJECT_NAME}/graph.c
src/${PROJECT_NAME}/names.c
src/${PROJECT_NAME}/types.c
)
@@ -91,7 +92,11 @@ if(BUILD_TESTING)
target_link_libraries(test_action_client
${PROJECT_NAME}
)
- ament_target_dependencies(test_action_client "osrf_testing_tools_cpp" "rcl" "test_msgs")
+ ament_target_dependencies(test_action_client
+ "osrf_testing_tools_cpp"
+ "rcl"
+ "test_msgs"
+ )
endif()
# get the rmw implementations ahead of time
@@ -122,6 +127,7 @@ if(BUILD_TESTING)
${PROJECT_NAME}
)
ament_target_dependencies(${target}${target_suffix}
+ "osrf_testing_tools_cpp"
"rcl"
"test_msgs"
)
@@ -146,6 +152,13 @@ if(BUILD_TESTING)
"test/rcl_action/test_action_communication.cpp")
custom_test_c(test_action_interaction
"test/rcl_action/test_action_interaction.cpp")
+
+ # TODO(jacobperron): Graph tests fail with opensplice. Re-enable after resolving
+ # https://github.com/ros2/ros2/issues/677
+ if(NOT rmw_implementation STREQUAL "rmw_opensplice_cpp")
+ custom_test_c(test_graph
+ "test/rcl_action/test_graph.cpp")
+ endif()
endmacro()
call_for_each_rmw_implementation(targets)
diff --git a/rcl_action/include/rcl_action/graph.h b/rcl_action/include/rcl_action/graph.h
new file mode 100644
index 000000000..7d4fc82e6
--- /dev/null
+++ b/rcl_action/include/rcl_action/graph.h
@@ -0,0 +1,162 @@
+// Copyright 2019 Open Source Robotics Foundation, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef RCL_ACTION__GRAPH_H_
+#define RCL_ACTION__GRAPH_H_
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+#include "rcl/graph.h"
+#include "rcl/node.h"
+
+#include "rcl_action/visibility_control.h"
+
+/// Get a list of action names and types for action clients associated with a node.
+/**
+ * The `node` parameter must point to a valid node.
+ *
+ * The `action_names_and_types` parameter must be allocated and zero initialized.
+ * This function allocates memory for the returned list of names and types and so it is the
+ * callers responsibility to pass `action_names_and_types` 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 action clients or action servers with names returned by this function may
+ * not result in the desired action name 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
+ *
+ * \param[in] node the handle to the node being used to query the ROS graph
+ * \param[in] allocator allocator for allocating space for strings
+ * \param[in] node_name the node name of the actions to return
+ * \param[in] node_namespace the node namespace of the actions to return
+ * \param[out] action_names_and_types list of action 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_ACTION_PUBLIC
+RCL_WARN_UNUSED
+rcl_ret_t
+rcl_action_get_client_names_and_types_by_node(
+ const rcl_node_t * node,
+ rcl_allocator_t * allocator,
+ const char * node_name,
+ const char * node_namespace,
+ rcl_names_and_types_t * action_names_and_types);
+
+/// Get a list of action names and types for action servers associated with a node.
+/**
+ * This function returns a list of action names and types for action servers associated with
+ * the provided node name.
+ *
+ * The `node` parameter must point to a valid node.
+ *
+ * The `action_names_and_types` parameter must be allocated and zero initialized.
+ * This function allocates memory for the returned list of names and types and so it is the
+ * callers responsibility to pass `action_names_and_types` 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 action clients or action servers with names returned by this function may
+ * not result in the desired action name 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
+ *
+ * \param[in] node the handle to the node being used to query the ROS graph
+ * \param[in] allocator allocator for allocating space for strings
+ * \param[in] node_name the node name of the actions to return
+ * \param[in] node_namespace the node namespace of the actions to return
+ * \param[out] action_names_and_types list of action 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_ACTION_PUBLIC
+RCL_WARN_UNUSED
+rcl_ret_t
+rcl_action_get_server_names_and_types_by_node(
+ const rcl_node_t * node,
+ rcl_allocator_t * allocator,
+ const char * node_name,
+ const char * node_namespace,
+ rcl_names_and_types_t * action_names_and_types);
+
+/// Return a list of action names and their types.
+/**
+ * This function returns a list of action names and types in the ROS graph.
+ *
+ * The `node` parameter must point to a valid node.
+ *
+ * The `action_names_and_types` parameter must be allocated and zero initialized.
+ * This function allocates memory for the returned list of names and types and so it is the
+ * callers responsibility to pass `action_names_and_types` 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 action clients or action servers with names returned by this function may
+ * not result in the desired action name 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
+ *
+ * \param[in] node the handle to the node being used to query the ROS graph
+ * \param[in] allocator allocator for allocating space for strings
+ * \param[out] action_names_and_types list of action names and 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_ACTION_PUBLIC
+RCL_WARN_UNUSED
+rcl_ret_t
+rcl_action_get_names_and_types(
+ const rcl_node_t * node,
+ rcl_allocator_t * allocator,
+ rcl_names_and_types_t * action_names_and_types);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // RCL_ACTION__GRAPH_H_
diff --git a/rcl_action/include/rcl_action/rcl_action.h b/rcl_action/include/rcl_action/rcl_action.h
index f99130eac..c7a33bb2d 100644
--- a/rcl_action/include/rcl_action/rcl_action.h
+++ b/rcl_action/include/rcl_action/rcl_action.h
@@ -52,6 +52,7 @@ extern "C"
#include "rcl_action/default_qos.h"
#include "rcl_action/goal_handle.h"
#include "rcl_action/goal_state_machine.h"
+#include "rcl_action/graph.h"
#include "rcl_action/types.h"
#include "rcl_action/wait.h"
diff --git a/rcl_action/src/rcl_action/graph.c b/rcl_action/src/rcl_action/graph.c
new file mode 100644
index 000000000..ce8474234
--- /dev/null
+++ b/rcl_action/src/rcl_action/graph.c
@@ -0,0 +1,221 @@
+// Copyright 2019 Open Source Robotics Foundation, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+#include
+#include
+
+#include "rcl/error_handling.h"
+#include "rcl/graph.h"
+#include "rcl/node.h"
+#include "rcutils/strdup.h"
+
+#include "rcl_action/graph.h"
+
+static
+rcl_ret_t
+_filter_action_names(
+ rcl_names_and_types_t * topic_names_and_types,
+ rcl_allocator_t * allocator,
+ rcl_names_and_types_t * action_names_and_types)
+{
+ assert(topic_names_and_types);
+ assert(allocator);
+ assert(action_names_and_types);
+
+ // Assumption: actions provide a topic name with the suffix "/_action/feedback"
+ // and it has type with the suffix "_FeedbackMessage"
+ const char * action_name_identifier = "/_action/feedback";
+ const char * action_type_identifier = "_FeedbackMessage";
+
+ rcl_ret_t ret;
+ const size_t num_names = topic_names_and_types->names.size;
+ char ** names = topic_names_and_types->names.data;
+
+ // Count number of actions to determine how much memory to allocate
+ size_t num_actions = 0u;
+ for (size_t i = 0u; i < num_names; ++i) {
+ const char * identifier_index = strstr(names[i], action_name_identifier);
+ if (identifier_index && strlen(identifier_index) == strlen(action_name_identifier)) {
+ ++num_actions;
+ }
+ }
+
+ if (0u == num_actions) {
+ return RCL_RET_OK;
+ }
+
+ ret = rcl_names_and_types_init(action_names_and_types, num_actions, allocator);
+ if (RCL_RET_OK != ret) {
+ return ret;
+ }
+
+ ret = RCL_RET_OK;
+
+ // Prune names/types that are not actions (ie. do not contain the suffix)
+ const size_t suffix_len = strlen(action_name_identifier);
+ size_t j = 0u;
+ for (size_t i = 0u; i < num_names; ++i) {
+ const char * identifier_index = strstr(names[i], action_name_identifier);
+ if (identifier_index && strlen(identifier_index) == strlen(action_name_identifier)) {
+ const size_t action_name_len = strlen(names[i]) - suffix_len;
+ char * action_name = rcutils_strndup(names[i], action_name_len, *allocator);
+ if (!action_name) {
+ RCL_SET_ERROR_MSG("Failed to allocate memory for action name");
+ ret = RCL_RET_BAD_ALLOC;
+ break;
+ }
+
+ action_names_and_types->names.data[j] = action_name;
+
+ // Allocate storage for type list
+ rcutils_ret_t rcutils_ret = rcutils_string_array_init(
+ &action_names_and_types->types[j],
+ topic_names_and_types->types[i].size,
+ allocator);
+ if (RCUTILS_RET_OK != rcutils_ret) {
+ RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
+ ret = RCL_RET_BAD_ALLOC;
+ break;
+ }
+
+ // Populate types list
+ for (size_t k = 0u; k < topic_names_and_types->types[i].size; ++k) {
+ char * type_name = topic_names_and_types->types[i].data[k];
+ size_t action_type_len = strlen(type_name);
+ // Trim type name suffix
+ const size_t type_suffix_len = strlen(action_type_identifier);
+ const char * type_identifier_index = strstr(type_name, action_type_identifier);
+ if (type_identifier_index &&
+ strlen(type_identifier_index) == strlen(action_type_identifier))
+ {
+ action_type_len = strlen(type_name) - type_suffix_len;
+ }
+ // Copy name to output struct
+ char * action_type_name = rcutils_strndup(type_name, action_type_len, *allocator);
+ if (!action_type_name) {
+ RCL_SET_ERROR_MSG("Failed to allocate memory for action type");
+ ret = RCL_RET_BAD_ALLOC;
+ break;
+ }
+ action_names_and_types->types[j].data[k] = action_type_name;
+ }
+ ++j;
+ }
+ }
+
+ // Cleanup if there is an error
+ if (RCL_RET_OK != ret) {
+ rcl_ret_t fini_ret = rcl_names_and_types_fini(action_names_and_types);
+ (void)fini_ret; // Error already set
+ }
+
+ return ret;
+}
+
+rcl_ret_t
+rcl_action_get_client_names_and_types_by_node(
+ const rcl_node_t * node,
+ rcl_allocator_t * allocator,
+ const char * node_name,
+ const char * node_namespace,
+ rcl_names_and_types_t * action_names_and_types)
+{
+ RCL_CHECK_ARGUMENT_FOR_NULL(action_names_and_types, RCL_RET_INVALID_ARGUMENT);
+
+ rcl_ret_t ret;
+ rcl_names_and_types_t topic_names_and_types = rcl_get_zero_initialized_names_and_types();
+ ret = rcl_get_subscriber_names_and_types_by_node(
+ node, allocator, false, node_name, node_namespace, &topic_names_and_types);
+ if (RCL_RET_OK != ret) {
+ return ret;
+ }
+
+ ret = _filter_action_names(
+ &topic_names_and_types,
+ allocator,
+ action_names_and_types);
+
+ rcl_ret_t nat_fini_ret = rcl_names_and_types_fini(&topic_names_and_types);
+ if (RCL_RET_OK != nat_fini_ret) {
+ ret = rcl_names_and_types_fini(action_names_and_types);
+ return nat_fini_ret;
+ }
+ return ret;
+}
+
+rcl_ret_t
+rcl_action_get_server_names_and_types_by_node(
+ const rcl_node_t * node,
+ rcl_allocator_t * allocator,
+ const char * node_name,
+ const char * node_namespace,
+ rcl_names_and_types_t * action_names_and_types)
+{
+ RCL_CHECK_ARGUMENT_FOR_NULL(action_names_and_types, RCL_RET_INVALID_ARGUMENT);
+
+ rcl_ret_t ret;
+ rcl_names_and_types_t topic_names_and_types = rcl_get_zero_initialized_names_and_types();
+ ret = rcl_get_publisher_names_and_types_by_node(
+ node, allocator, false, node_name, node_namespace, &topic_names_and_types);
+ if (RCL_RET_OK != ret) {
+ return ret;
+ }
+
+ ret = _filter_action_names(
+ &topic_names_and_types,
+ allocator,
+ action_names_and_types);
+
+ rcl_ret_t nat_fini_ret = rcl_names_and_types_fini(&topic_names_and_types);
+ if (RCL_RET_OK != nat_fini_ret) {
+ ret = rcl_names_and_types_fini(action_names_and_types);
+ return nat_fini_ret;
+ }
+ return ret;
+}
+
+rcl_ret_t
+rcl_action_get_names_and_types(
+ const rcl_node_t * node,
+ rcl_allocator_t * allocator,
+ rcl_names_and_types_t * action_names_and_types)
+{
+ RCL_CHECK_ARGUMENT_FOR_NULL(action_names_and_types, RCL_RET_INVALID_ARGUMENT);
+ rcl_names_and_types_t topic_names_and_types = rcl_get_zero_initialized_names_and_types();
+ rcl_ret_t ret = rcl_get_topic_names_and_types(node, allocator, false, &topic_names_and_types);
+ if (RCL_RET_OK != ret) {
+ return ret;
+ }
+
+ ret = _filter_action_names(
+ &topic_names_and_types,
+ allocator,
+ action_names_and_types);
+
+ rcl_ret_t nat_fini_ret = rcl_names_and_types_fini(&topic_names_and_types);
+ if (RCL_RET_OK != nat_fini_ret) {
+ ret = rcl_names_and_types_fini(action_names_and_types);
+ return nat_fini_ret;
+ }
+ return ret;
+}
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/rcl_action/test/rcl_action/test_graph.cpp b/rcl_action/test/rcl_action/test_graph.cpp
new file mode 100644
index 000000000..c35ac5baa
--- /dev/null
+++ b/rcl_action/test/rcl_action/test_graph.cpp
@@ -0,0 +1,563 @@
+// Copyright 2019 Open Source Robotics Foundation, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include
+
+#include
+#include
+
+#include "rcl_action/action_client.h"
+#include "rcl_action/action_server.h"
+#include "rcl_action/graph.h"
+
+#include "rcl/error_handling.h"
+#include "rcl/rcl.h"
+
+#include "osrf_testing_tools_cpp/scope_exit.hpp"
+
+#include "test_msgs/action/fibonacci.h"
+
+#ifdef RMW_IMPLEMENTATION
+# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
+# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
+#else
+# define CLASSNAME(NAME, SUFFIX) NAME
+#endif
+
+class CLASSNAME (TestActionGraphFixture, RMW_IMPLEMENTATION) : public ::testing::Test
+{
+public:
+ rcl_allocator_t allocator = rcl_get_default_allocator();
+ rcl_allocator_t zero_allocator;
+ rcl_context_t old_context;
+ rcl_context_t context;
+ rcl_node_t old_node;
+ rcl_node_t node;
+ rcl_node_t zero_node;
+ const char * test_graph_node_name = "test_action_graph_node";
+ const char * test_graph_old_node_name = "test_action_graph_old_node_name";
+
+ void SetUp()
+ {
+ rcl_ret_t ret;
+ this->zero_node = rcl_get_zero_initialized_node();
+ this->zero_allocator = static_cast(rcutils_get_zero_initialized_allocator());
+
+ rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
+ ret = rcl_init_options_init(&init_options, this->allocator);
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str;
+ });
+ this->old_context = rcl_get_zero_initialized_context();
+ ret = rcl_init(0, nullptr, &init_options, &this->old_context);
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ this->old_node = rcl_get_zero_initialized_node();
+ rcl_node_options_t node_options = rcl_node_get_default_options();
+ ret = rcl_node_init(
+ &this->old_node, this->test_graph_old_node_name, "", &this->old_context, &node_options);
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ ret = rcl_shutdown(&this->old_context); // after this, the old_node should be invalid
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ this->context = rcl_get_zero_initialized_context();
+ ret = rcl_init(0, nullptr, &init_options, &this->context);
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ this->node = rcl_get_zero_initialized_node();
+ ret = rcl_node_init(&this->node, test_graph_node_name, "", &this->context, &node_options);
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ }
+
+ void TearDown()
+ {
+ rcl_ret_t ret;
+ ret = rcl_node_fini(&this->old_node);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ ret = rcl_node_fini(&this->node);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ ret = rcl_shutdown(&this->context);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ ret = rcl_context_fini(&this->context);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ ret = rcl_context_fini(&this->old_context);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ }
+};
+
+TEST_F(
+ CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION),
+ test_action_get_client_names_and_types_by_node)
+{
+ rcl_ret_t ret;
+ rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
+
+ // Invalid node
+ ret = rcl_action_get_client_names_and_types_by_node(
+ nullptr, &this->allocator, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ ret = rcl_action_get_client_names_and_types_by_node(
+ &this->zero_node, &this->allocator, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ ret = rcl_action_get_client_names_and_types_by_node(
+ &this->old_node, &this->allocator, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Invalid allocator
+ ret = rcl_action_get_client_names_and_types_by_node(
+ &this->node, nullptr, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ ret = rcl_action_get_client_names_and_types_by_node(
+ &this->node, &this->zero_allocator, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Invalid node name
+ ret = rcl_action_get_client_names_and_types_by_node(
+ &this->node, &this->allocator, "_test_this_Isnot_a_valid_name", "", &nat);
+ EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Non-existent node
+ ret = rcl_action_get_client_names_and_types_by_node(
+ &this->node, &this->allocator, this->test_graph_old_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Invalid names and types
+ ret = rcl_action_get_client_names_and_types_by_node(
+ &this->node, &this->allocator, this->test_graph_node_name, "", nullptr);
+ EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Valid call
+ ret = rcl_action_get_client_names_and_types_by_node(
+ &this->node, &this->allocator, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ ret = rcl_names_and_types_fini(&nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+}
+
+TEST_F(
+ CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION),
+ test_action_get_server_names_and_types_by_node)
+{
+ rcl_ret_t ret;
+ rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
+
+ // Invalid node
+ ret = rcl_action_get_server_names_and_types_by_node(
+ nullptr, &this->allocator, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ ret = rcl_action_get_server_names_and_types_by_node(
+ &this->zero_node, &this->allocator, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ ret = rcl_action_get_server_names_and_types_by_node(
+ &this->old_node, &this->allocator, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Invalid allocator
+ ret = rcl_action_get_server_names_and_types_by_node(
+ &this->node, nullptr, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ ret = rcl_action_get_server_names_and_types_by_node(
+ &this->node, &this->zero_allocator, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Invalid node name
+ ret = rcl_action_get_server_names_and_types_by_node(
+ &this->node, &this->allocator, "_test_this_Isnot_a_valid_name", "", &nat);
+ EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Non-existent node
+ ret = rcl_action_get_server_names_and_types_by_node(
+ &this->node, &this->allocator, this->test_graph_old_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Invalid names and types
+ ret = rcl_action_get_server_names_and_types_by_node(
+ &this->node, &this->allocator, this->test_graph_node_name, "", nullptr);
+ EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Valid call
+ ret = rcl_action_get_server_names_and_types_by_node(
+ &this->node, &this->allocator, this->test_graph_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ ret = rcl_names_and_types_fini(&nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+}
+
+TEST_F(
+ CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION),
+ test_action_get_names_and_types)
+{
+ rcl_ret_t ret;
+ rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
+
+ // Invalid node
+ ret = rcl_action_get_names_and_types(nullptr, &this->allocator, &nat);
+ EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ ret = rcl_action_get_names_and_types(&this->zero_node, &this->allocator, &nat);
+ EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ ret = rcl_action_get_names_and_types(&this->old_node, &this->allocator, &nat);
+ EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Invalid allocator
+ ret = rcl_action_get_names_and_types(&this->node, nullptr, &nat);
+ EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ ret = rcl_action_get_names_and_types(&this->node, &this->zero_allocator, &nat);
+ EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Invalid names and types
+ ret = rcl_action_get_names_and_types(&this->node, &this->allocator, nullptr);
+ EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
+ rcl_reset_error();
+ // Valid call
+ ret = rcl_action_get_names_and_types(&this->node, &this->allocator, &nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ ret = rcl_names_and_types_fini(&nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+}
+
+/**
+ * Type define a get actions function.
+ */
+typedef std::function GetActionsFunc;
+
+/**
+ * Extend the TestActionGraphFixture with a multi-node fixture for node discovery and node-graph
+ * perspective.
+ */
+class TestActionGraphMultiNodeFixture : public CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION)
+{
+public:
+ const char * remote_node_name = "remote_graph_node";
+ const char * action_name = "/test_action_info_functions__";
+ rcl_node_t remote_node;
+ rcl_context_t remote_context;
+ GetActionsFunc action_func, clients_by_node_func, servers_by_node_func;
+
+ void SetUp() override
+ {
+ CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION) ::SetUp();
+
+ rcl_ret_t ret;
+ rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
+ ret = rcl_init_options_init(&init_options, rcl_get_default_allocator());
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) <<
+ rcl_get_error_string().str;
+ });
+
+ this->remote_node = rcl_get_zero_initialized_node();
+ rcl_node_options_t node_options = rcl_node_get_default_options();
+
+ this->remote_context = rcl_get_zero_initialized_context();
+ ret = rcl_init(0, nullptr, &init_options, &this->remote_context);
+
+ ret = rcl_node_init(
+ &this->remote_node, this->remote_node_name, "", &this->remote_context, &node_options);
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ action_func = std::bind(rcl_action_get_names_and_types,
+ std::placeholders::_1,
+ &this->allocator,
+ std::placeholders::_2);
+ clients_by_node_func = std::bind(rcl_action_get_client_names_and_types_by_node,
+ std::placeholders::_1,
+ &this->allocator,
+ this->remote_node_name,
+ "",
+ std::placeholders::_2);
+ servers_by_node_func = std::bind(rcl_action_get_server_names_and_types_by_node,
+ std::placeholders::_1,
+ &this->allocator,
+ this->remote_node_name,
+ "",
+ std::placeholders::_2);
+ WaitForAllNodesAlive();
+ }
+
+ void TearDown() override
+ {
+ CLASSNAME(TestActionGraphFixture, RMW_IMPLEMENTATION) ::TearDown();
+
+ rcl_ret_t ret;
+ ret = rcl_node_fini(&this->remote_node);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ ret = rcl_shutdown(&this->remote_context);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ ret = rcl_context_fini(&this->remote_context);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ }
+
+ void WaitForAllNodesAlive()
+ {
+ rcl_ret_t ret;
+ rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array();
+ rcutils_string_array_t node_namespaces = rcutils_get_zero_initialized_string_array();
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ ret = rcutils_string_array_fini(&node_names);
+ ASSERT_EQ(RCUTILS_RET_OK, ret);
+ ret = rcutils_string_array_fini(&node_namespaces);
+ ASSERT_EQ(RCUTILS_RET_OK, ret);
+ });
+ // Wait for all 3 nodes to be discovered: remote_node, old_node, node
+ size_t attempts = 0u;
+ size_t max_attempts = 4u;
+ while (node_names.size < 3u) {
+ std::this_thread::sleep_for(std::chrono::seconds(1));
+ ret = rcl_get_node_names(&this->remote_node, allocator, &node_names, &node_namespaces);
+ ++attempts;
+ ASSERT_LE(attempts, max_attempts) << "Unable to attain all required nodes";
+ }
+ }
+
+ void WaitForActionCount(
+ GetActionsFunc func,
+ size_t expected_count,
+ std::chrono::milliseconds duration)
+ {
+ auto start_time = std::chrono::system_clock::now();
+ auto curr_time = start_time;
+
+ rcl_ret_t ret;
+ while ((curr_time - start_time) < duration) {
+ rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
+ ret = func(&this->node, &nat);
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ size_t action_count = nat.names.size;
+ ret = rcl_names_and_types_fini(&nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ if (action_count == expected_count) {
+ return;
+ }
+ std::this_thread::sleep_for(std::chrono::milliseconds(200));
+ curr_time = std::chrono::system_clock::now();
+ }
+ }
+};
+
+// Note, this test could be affected by other communication on the same ROS domain
+TEST_F(TestActionGraphMultiNodeFixture, test_action_get_names_and_types) {
+ rcl_ret_t ret;
+ // Create an action client
+ rcl_action_client_t action_client = rcl_action_get_zero_initialized_client();
+ const rosidl_action_type_support_t * action_typesupport =
+ ROSIDL_GET_ACTION_TYPE_SUPPORT(test_msgs, Fibonacci);
+ const char * client_action_name = "/test_action_get_names_and_types_client_action_name";
+ rcl_action_client_options_t action_client_options = rcl_action_client_get_default_options();
+ ret = rcl_action_client_init(
+ &action_client,
+ &this->remote_node,
+ action_typesupport,
+ client_action_name,
+ &action_client_options);
+ ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_action_client_fini(&action_client, &this->remote_node)) <<
+ rcl_get_error_string().str;
+ });
+
+ WaitForActionCount(action_func, 1u, std::chrono::seconds(1));
+
+ // Check that there is exactly one action name
+ rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
+ ret = action_func(&this->node, &nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ ASSERT_EQ(nat.names.size, 1u);
+ EXPECT_STREQ(nat.names.data[0], client_action_name);
+ ASSERT_EQ(nat.types[0].size, 1u);
+ EXPECT_STREQ(nat.types[0].data[0], "test_msgs/Fibonacci");
+
+ ret = rcl_names_and_types_fini(&nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ // Create an action server
+ rcl_action_server_t action_server = rcl_action_get_zero_initialized_server();
+ rcl_clock_t clock;
+ ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &this->allocator);
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string().str;
+ });
+ const char * server_action_name = "/test_action_get_names_and_types_server_action_name";
+ rcl_action_server_options_t action_server_options = rcl_action_server_get_default_options();
+ ret = rcl_action_server_init(
+ &action_server,
+ &this->remote_node,
+ &clock,
+ action_typesupport,
+ server_action_name,
+ &action_server_options);
+ ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_action_server_fini(&action_server, &this->remote_node)) <<
+ rcl_get_error_string().str;
+ });
+
+ WaitForActionCount(action_func, 2u, std::chrono::seconds(1));
+
+ ret = action_func(&this->node, &nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ ASSERT_EQ(nat.names.size, 2u);
+ EXPECT_STREQ(nat.names.data[0], client_action_name);
+ EXPECT_STREQ(nat.names.data[1], server_action_name);
+ ASSERT_EQ(nat.types[0].size, 1u);
+ EXPECT_STREQ(nat.types[0].data[0], "test_msgs/Fibonacci");
+ ASSERT_EQ(nat.types[1].size, 1u);
+ EXPECT_STREQ(nat.types[1].data[0], "test_msgs/Fibonacci");
+
+ ret = rcl_names_and_types_fini(&nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+}
+
+// Note, this test could be affected by other communication on the same ROS domain
+TEST_F(TestActionGraphMultiNodeFixture, test_action_get_server_names_and_types_by_node) {
+ rcl_ret_t ret;
+ // Create an action client
+ rcl_action_client_t action_client = rcl_action_get_zero_initialized_client();
+ const rosidl_action_type_support_t * action_typesupport =
+ ROSIDL_GET_ACTION_TYPE_SUPPORT(test_msgs, Fibonacci);
+ rcl_action_client_options_t action_client_options = rcl_action_client_get_default_options();
+ ret = rcl_action_client_init(
+ &action_client,
+ &this->remote_node,
+ action_typesupport,
+ this->action_name,
+ &action_client_options);
+ ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_action_client_fini(&action_client, &this->remote_node)) <<
+ rcl_get_error_string().str;
+ });
+ // Check that there are no action servers
+ rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
+ ret = rcl_action_get_server_names_and_types_by_node(
+ &this->node, &this->allocator, this->remote_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ ASSERT_EQ(nat.names.size, 0u);
+
+ ret = rcl_names_and_types_fini(&nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ // Create an action server
+ rcl_action_server_t action_server = rcl_action_get_zero_initialized_server();
+ rcl_clock_t clock;
+ ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &this->allocator);
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string().str;
+ });
+ rcl_action_server_options_t action_server_options = rcl_action_server_get_default_options();
+ ret = rcl_action_server_init(
+ &action_server,
+ &this->remote_node,
+ &clock,
+ action_typesupport,
+ this->action_name,
+ &action_server_options);
+ ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_action_server_fini(&action_server, &this->remote_node)) <<
+ rcl_get_error_string().str;
+ });
+
+ WaitForActionCount(servers_by_node_func, 1u, std::chrono::seconds(1));
+ ret = servers_by_node_func(&this->node, &nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ ASSERT_EQ(nat.names.size, 1u);
+ EXPECT_STREQ(nat.names.data[0], this->action_name);
+ ASSERT_EQ(nat.types[0].size, 1u);
+ EXPECT_STREQ(nat.types[0].data[0], "test_msgs/Fibonacci");
+
+ ret = rcl_names_and_types_fini(&nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+}
+
+// Note, this test could be affected by other communication on the same ROS domain
+TEST_F(TestActionGraphMultiNodeFixture, test_action_get_client_names_and_types_by_node) {
+ rcl_ret_t ret;
+ const rosidl_action_type_support_t * action_typesupport =
+ ROSIDL_GET_ACTION_TYPE_SUPPORT(test_msgs, Fibonacci);
+ // Create an action server
+ rcl_action_server_t action_server = rcl_action_get_zero_initialized_server();
+ rcl_clock_t clock;
+ ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &this->allocator);
+ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string().str;
+ });
+ rcl_action_server_options_t action_server_options = rcl_action_server_get_default_options();
+ ret = rcl_action_server_init(
+ &action_server,
+ &this->remote_node,
+ &clock,
+ action_typesupport,
+ this->action_name,
+ &action_server_options);
+ ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_action_server_fini(&action_server, &this->remote_node)) <<
+ rcl_get_error_string().str;
+ });
+
+ // Check that there are no action clients
+ rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
+ ret = rcl_action_get_client_names_and_types_by_node(
+ &this->node, &this->allocator, this->remote_node_name, "", &nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ ASSERT_EQ(nat.names.size, 0u);
+
+ ret = rcl_names_and_types_fini(&nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+
+ // Create an action client
+ rcl_action_client_t action_client = rcl_action_get_zero_initialized_client();
+ rcl_action_client_options_t action_client_options = rcl_action_client_get_default_options();
+ ret = rcl_action_client_init(
+ &action_client,
+ &this->remote_node,
+ action_typesupport,
+ this->action_name,
+ &action_client_options);
+ ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
+ EXPECT_EQ(RCL_RET_OK, rcl_action_client_fini(&action_client, &this->remote_node)) <<
+ rcl_get_error_string().str;
+ });
+
+ WaitForActionCount(clients_by_node_func, 1u, std::chrono::seconds(1));
+ ret = clients_by_node_func(&this->node, &nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+ ASSERT_EQ(nat.names.size, 1u);
+ EXPECT_STREQ(nat.names.data[0], this->action_name);
+ ASSERT_EQ(nat.types[0].size, 1u);
+ EXPECT_STREQ(nat.types[0].data[0], "test_msgs/Fibonacci");
+
+ ret = rcl_names_and_types_fini(&nat);
+ EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
+}