rename rosidl_generator_c namespace to rosidl_runtime_c (#616)
Signed-off-by: Dirk Thomas <dirk-thomas@users.noreply.github.com>
This commit is contained in:
parent
88fd4b0313
commit
94b5a1d7d0
17 changed files with 49 additions and 49 deletions
|
@ -20,7 +20,7 @@ extern "C"
|
||||||
{
|
{
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "rosidl_generator_c/service_type_support_struct.h"
|
#include "rosidl_runtime_c/service_type_support_struct.h"
|
||||||
|
|
||||||
#include "rcl/macros.h"
|
#include "rcl/macros.h"
|
||||||
#include "rcl/node.h"
|
#include "rcl/node.h"
|
||||||
|
@ -75,7 +75,7 @@ rcl_get_zero_initialized_client(void);
|
||||||
* For C, a macro can be used (for example `example_interfaces/AddTwoInts`):
|
* For C, a macro can be used (for example `example_interfaces/AddTwoInts`):
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rosidl_generator_c/service_type_support_struct.h>
|
* #include <rosidl_runtime_c/service_type_support_struct.h>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
*
|
*
|
||||||
* const rosidl_service_type_support_t * ts =
|
* const rosidl_service_type_support_t * ts =
|
||||||
|
@ -109,7 +109,7 @@ rcl_get_zero_initialized_client(void);
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rcl/rcl.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <rosidl_generator_c/service_type_support_struct.h>
|
* #include <rosidl_runtime_c/service_type_support_struct.h>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
|
|
|
@ -26,7 +26,7 @@ extern "C"
|
||||||
|
|
||||||
#include "rcutils/types.h"
|
#include "rcutils/types.h"
|
||||||
|
|
||||||
#include "rosidl_generator_c/service_type_support_struct.h"
|
#include "rosidl_runtime_c/service_type_support_struct.h"
|
||||||
|
|
||||||
#include "rcl/macros.h"
|
#include "rcl/macros.h"
|
||||||
#include "rcl/client.h"
|
#include "rcl/client.h"
|
||||||
|
|
|
@ -20,7 +20,7 @@ extern "C"
|
||||||
{
|
{
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "rosidl_generator_c/message_type_support_struct.h"
|
#include "rosidl_runtime_c/message_type_support_struct.h"
|
||||||
|
|
||||||
#include "rcl/macros.h"
|
#include "rcl/macros.h"
|
||||||
#include "rcl/node.h"
|
#include "rcl/node.h"
|
||||||
|
@ -74,7 +74,7 @@ rcl_get_zero_initialized_publisher(void);
|
||||||
* For C, a macro can be used (for example `std_msgs/String`):
|
* For C, a macro can be used (for example `std_msgs/String`):
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rosidl_generator_c/message_type_support_struct.h>
|
* #include <rosidl_runtime_c/message_type_support_struct.h>
|
||||||
* #include <std_msgs/msg/string.h>
|
* #include <std_msgs/msg/string.h>
|
||||||
* const rosidl_message_type_support_t * string_ts =
|
* const rosidl_message_type_support_t * string_ts =
|
||||||
* ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
* ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
||||||
|
@ -105,7 +105,7 @@ rcl_get_zero_initialized_publisher(void);
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rcl/rcl.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <rosidl_generator_c/message_type_support_struct.h>
|
* #include <rosidl_runtime_c/message_type_support_struct.h>
|
||||||
* #include <std_msgs/msg/string.h>
|
* #include <std_msgs/msg/string.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
|
|
|
@ -20,7 +20,7 @@ extern "C"
|
||||||
{
|
{
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "rosidl_generator_c/service_type_support_struct.h"
|
#include "rosidl_runtime_c/service_type_support_struct.h"
|
||||||
|
|
||||||
#include "rcl/macros.h"
|
#include "rcl/macros.h"
|
||||||
#include "rcl/node.h"
|
#include "rcl/node.h"
|
||||||
|
@ -73,7 +73,7 @@ rcl_get_zero_initialized_service(void);
|
||||||
* For C, a macro can be used (for example `example_interfaces/AddTwoInts`):
|
* For C, a macro can be used (for example `example_interfaces/AddTwoInts`):
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rosidl_generator_c/service_type_support_struct.h>
|
* #include <rosidl_runtime_c/service_type_support_struct.h>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
* const rosidl_service_type_support_t * ts =
|
* const rosidl_service_type_support_t * ts =
|
||||||
* ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts);
|
* ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts);
|
||||||
|
@ -105,7 +105,7 @@ rcl_get_zero_initialized_service(void);
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rcl/rcl.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <rosidl_generator_c/service_type_support_struct.h>
|
* #include <rosidl_runtime_c/service_type_support_struct.h>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
|
|
|
@ -20,7 +20,7 @@ extern "C"
|
||||||
{
|
{
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "rosidl_generator_c/message_type_support_struct.h"
|
#include "rosidl_runtime_c/message_type_support_struct.h"
|
||||||
|
|
||||||
#include "rcl/macros.h"
|
#include "rcl/macros.h"
|
||||||
#include "rcl/node.h"
|
#include "rcl/node.h"
|
||||||
|
@ -73,7 +73,7 @@ rcl_get_zero_initialized_subscription(void);
|
||||||
* For C a macro can be used (for example `std_msgs/String`):
|
* For C a macro can be used (for example `std_msgs/String`):
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rosidl_generator_c/message_type_support_struct.h>
|
* #include <rosidl_runtime_c/message_type_support_struct.h>
|
||||||
* #include <std_msgs/msg/string.h>
|
* #include <std_msgs/msg/string.h>
|
||||||
* const rosidl_message_type_support_t * string_ts =
|
* const rosidl_message_type_support_t * string_ts =
|
||||||
* ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
* ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
||||||
|
@ -106,7 +106,7 @@ rcl_get_zero_initialized_subscription(void);
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rcl/rcl.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <rosidl_generator_c/message_type_support_struct.h>
|
* #include <rosidl_runtime_c/message_type_support_struct.h>
|
||||||
* #include <std_msgs/msg/string.h>
|
* #include <std_msgs/msg/string.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
#include "rcutils/macros.h"
|
#include "rcutils/macros.h"
|
||||||
#include "rcutils/types/hash_map.h"
|
#include "rcutils/types/hash_map.h"
|
||||||
#include "rcutils/types/rcutils_ret.h"
|
#include "rcutils/types/rcutils_ret.h"
|
||||||
#include "rosidl_generator_c/string_functions.h"
|
#include "rosidl_runtime_c/string_functions.h"
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
extern "C"
|
extern "C"
|
||||||
|
@ -265,10 +265,10 @@ void rcl_logging_rosout_output_handler(
|
||||||
log_message->stamp.nanosec = (timestamp % RCL_S_TO_NS(1));
|
log_message->stamp.nanosec = (timestamp % RCL_S_TO_NS(1));
|
||||||
log_message->level = severity;
|
log_message->level = severity;
|
||||||
log_message->line = (int32_t) location->line_number;
|
log_message->line = (int32_t) location->line_number;
|
||||||
rosidl_generator_c__String__assign(&log_message->name, name);
|
rosidl_runtime_c__String__assign(&log_message->name, name);
|
||||||
rosidl_generator_c__String__assign(&log_message->msg, msg_array.buffer);
|
rosidl_runtime_c__String__assign(&log_message->msg, msg_array.buffer);
|
||||||
rosidl_generator_c__String__assign(&log_message->file, location->file_name);
|
rosidl_runtime_c__String__assign(&log_message->file, location->file_name);
|
||||||
rosidl_generator_c__String__assign(&log_message->function, location->function_name);
|
rosidl_runtime_c__String__assign(&log_message->function, location->function_name);
|
||||||
status = rcl_publish(&entry.publisher, log_message, NULL);
|
status = rcl_publish(&entry.publisher, log_message, NULL);
|
||||||
if (RCL_RET_OK != status) {
|
if (RCL_RET_OK != status) {
|
||||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to publish log message to rosout: ");
|
RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to publish log message to rosout: ");
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
#include "rmw/incompatible_qos_events_statuses.h"
|
#include "rmw/incompatible_qos_events_statuses.h"
|
||||||
|
|
||||||
#include "test_msgs/msg/strings.h"
|
#include "test_msgs/msg/strings.h"
|
||||||
#include "rosidl_generator_c/string_functions.h"
|
#include "rosidl_runtime_c/string_functions.h"
|
||||||
|
|
||||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||||
|
|
||||||
|
@ -395,7 +395,7 @@ TEST_F(TestEventFixture, test_pubsub_no_deadline_missed)
|
||||||
{
|
{
|
||||||
test_msgs__msg__Strings msg;
|
test_msgs__msg__Strings msg;
|
||||||
test_msgs__msg__Strings__init(&msg);
|
test_msgs__msg__Strings__init(&msg);
|
||||||
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, test_string));
|
ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg.string_value, test_string));
|
||||||
ret = rcl_publish(&publisher, &msg, nullptr);
|
ret = rcl_publish(&publisher, &msg, nullptr);
|
||||||
test_msgs__msg__Strings__fini(&msg);
|
test_msgs__msg__Strings__fini(&msg);
|
||||||
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
||||||
|
@ -462,7 +462,7 @@ TEST_F(TestEventFixture, test_pubsub_deadline_missed)
|
||||||
{
|
{
|
||||||
test_msgs__msg__Strings msg;
|
test_msgs__msg__Strings msg;
|
||||||
test_msgs__msg__Strings__init(&msg);
|
test_msgs__msg__Strings__init(&msg);
|
||||||
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, test_string));
|
ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg.string_value, test_string));
|
||||||
ret = rcl_publish(&publisher, &msg, nullptr);
|
ret = rcl_publish(&publisher, &msg, nullptr);
|
||||||
test_msgs__msg__Strings__fini(&msg);
|
test_msgs__msg__Strings__fini(&msg);
|
||||||
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
||||||
|
@ -537,7 +537,7 @@ TEST_F(TestEventFixture, test_pubsub_liveliness_kill_pub)
|
||||||
{
|
{
|
||||||
test_msgs__msg__Strings msg;
|
test_msgs__msg__Strings msg;
|
||||||
test_msgs__msg__Strings__init(&msg);
|
test_msgs__msg__Strings__init(&msg);
|
||||||
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, test_string));
|
ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg.string_value, test_string));
|
||||||
ret = rcl_publish(&publisher, &msg, nullptr);
|
ret = rcl_publish(&publisher, &msg, nullptr);
|
||||||
test_msgs__msg__Strings__fini(&msg);
|
test_msgs__msg__Strings__fini(&msg);
|
||||||
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
#include "rmw/error_handling.h"
|
#include "rmw/error_handling.h"
|
||||||
|
|
||||||
#include "test_msgs/msg/strings.h"
|
#include "test_msgs/msg/strings.h"
|
||||||
#include "rosidl_generator_c/string_functions.h"
|
#include "rosidl_runtime_c/string_functions.h"
|
||||||
|
|
||||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||||
|
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
#include "rcl/rcl.h"
|
#include "rcl/rcl.h"
|
||||||
#include "test_msgs/msg/basic_types.h"
|
#include "test_msgs/msg/basic_types.h"
|
||||||
#include "test_msgs/msg/strings.h"
|
#include "test_msgs/msg/strings.h"
|
||||||
#include "rosidl_generator_c/string_functions.h"
|
#include "rosidl_runtime_c/string_functions.h"
|
||||||
|
|
||||||
#include "./failing_allocator_functions.hpp"
|
#include "./failing_allocator_functions.hpp"
|
||||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||||
|
@ -118,7 +118,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
|
||||||
});
|
});
|
||||||
test_msgs__msg__Strings msg;
|
test_msgs__msg__Strings msg;
|
||||||
test_msgs__msg__Strings__init(&msg);
|
test_msgs__msg__Strings__init(&msg);
|
||||||
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, "testing"));
|
ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg.string_value, "testing"));
|
||||||
ret = rcl_publish(&publisher, &msg, nullptr);
|
ret = rcl_publish(&publisher, &msg, nullptr);
|
||||||
test_msgs__msg__Strings__fini(&msg);
|
test_msgs__msg__Strings__fini(&msg);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
@ -171,7 +171,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff
|
||||||
|
|
||||||
test_msgs__msg__Strings msg_string;
|
test_msgs__msg__Strings msg_string;
|
||||||
test_msgs__msg__Strings__init(&msg_string);
|
test_msgs__msg__Strings__init(&msg_string);
|
||||||
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg_string.string_value, "testing"));
|
ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg_string.string_value, "testing"));
|
||||||
ret = rcl_publish(&publisher_in_namespace, &msg_string, nullptr);
|
ret = rcl_publish(&publisher_in_namespace, &msg_string, nullptr);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
}
|
}
|
||||||
|
|
|
@ -23,7 +23,7 @@
|
||||||
#include "rcl/rcl.h"
|
#include "rcl/rcl.h"
|
||||||
#include "test_msgs/msg/basic_types.h"
|
#include "test_msgs/msg/basic_types.h"
|
||||||
#include "test_msgs/msg/strings.h"
|
#include "test_msgs/msg/strings.h"
|
||||||
#include "rosidl_generator_c/string_functions.h"
|
#include "rosidl_runtime_c/string_functions.h"
|
||||||
|
|
||||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
|
@ -236,7 +236,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
|
||||||
{
|
{
|
||||||
test_msgs__msg__Strings msg;
|
test_msgs__msg__Strings msg;
|
||||||
test_msgs__msg__Strings__init(&msg);
|
test_msgs__msg__Strings__init(&msg);
|
||||||
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, test_string));
|
ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg.string_value, test_string));
|
||||||
ret = rcl_publish(&publisher, &msg, nullptr);
|
ret = rcl_publish(&publisher, &msg, nullptr);
|
||||||
test_msgs__msg__Strings__fini(&msg);
|
test_msgs__msg__Strings__fini(&msg);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
#include "rcl/rcl.h"
|
#include "rcl/rcl.h"
|
||||||
#include "rcl/graph.h"
|
#include "rcl/graph.h"
|
||||||
|
|
||||||
#include "rosidl_generator_c/string_functions.h"
|
#include "rosidl_runtime_c/string_functions.h"
|
||||||
#include "test_msgs/srv/basic_types.h"
|
#include "test_msgs/srv/basic_types.h"
|
||||||
|
|
||||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||||
|
|
|
@ -94,7 +94,7 @@ rcl_action_get_zero_initialized_client(void);
|
||||||
* For C, a macro can be used (for example `example_interfaces/Fibonacci`):
|
* For C, a macro can be used (for example `example_interfaces/Fibonacci`):
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rosidl_generator_c/action_type_support_struct.h>
|
* #include <rosidl_runtime_c/action_type_support_struct.h>
|
||||||
* #include <example_interfaces/action/fibonacci.h>
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
* const rosidl_action_type_support_t * ts =
|
* const rosidl_action_type_support_t * ts =
|
||||||
* ROSIDL_GET_ACTION_TYPE_SUPPORT(example_interfaces, Fibonacci);
|
* ROSIDL_GET_ACTION_TYPE_SUPPORT(example_interfaces, Fibonacci);
|
||||||
|
@ -127,7 +127,7 @@ rcl_action_get_zero_initialized_client(void);
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rcl/rcl.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <rcl_action/action_client.h>
|
* #include <rcl_action/action_client.h>
|
||||||
* #include <rosidl_generator_c/action_type_support_struct.h>
|
* #include <rosidl_runtime_c/action_type_support_struct.h>
|
||||||
* #include <example_interfaces/action/fibonacci.h>
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
|
|
|
@ -27,7 +27,7 @@ extern "C"
|
||||||
#include "rcl/node.h"
|
#include "rcl/node.h"
|
||||||
#include "rcl/time.h"
|
#include "rcl/time.h"
|
||||||
|
|
||||||
#include "rosidl_generator_c/action_type_support_struct.h"
|
#include "rosidl_runtime_c/action_type_support_struct.h"
|
||||||
|
|
||||||
/// Internal rcl_action implementation struct.
|
/// Internal rcl_action implementation struct.
|
||||||
struct rcl_action_server_impl_t;
|
struct rcl_action_server_impl_t;
|
||||||
|
@ -91,7 +91,7 @@ rcl_action_get_zero_initialized_server(void);
|
||||||
* For C, a macro can be used (for example `example_interfaces/Fibonacci`):
|
* For C, a macro can be used (for example `example_interfaces/Fibonacci`):
|
||||||
*
|
*
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rosidl_generator_c/action_type_support_struct.h>
|
* #include <rosidl_runtime_c/action_type_support_struct.h>
|
||||||
* #include <example_interfaces/action/fibonacci.h>
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
* const rosidl_action_type_support_t * ts =
|
* const rosidl_action_type_support_t * ts =
|
||||||
* ROSIDL_GET_ACTION_TYPE_SUPPORT(example_interfaces, Fibonacci);
|
* ROSIDL_GET_ACTION_TYPE_SUPPORT(example_interfaces, Fibonacci);
|
||||||
|
@ -124,7 +124,7 @@ rcl_action_get_zero_initialized_server(void);
|
||||||
* ```c
|
* ```c
|
||||||
* #include <rcl/rcl.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <rcl_action/rcl_action.h>
|
* #include <rcl_action/rcl_action.h>
|
||||||
* #include <rosidl_generator_c/action_type_support_struct.h>
|
* #include <rosidl_runtime_c/action_type_support_struct.h>
|
||||||
* #include <example_interfaces/action/fibonacci.h>
|
* #include <example_interfaces/action/fibonacci.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
|
|
|
@ -31,7 +31,7 @@ extern "C"
|
||||||
#include "rcl/macros.h"
|
#include "rcl/macros.h"
|
||||||
#include "rcl/types.h"
|
#include "rcl/types.h"
|
||||||
|
|
||||||
#include "rosidl_generator_c/action_type_support_struct.h"
|
#include "rosidl_runtime_c/action_type_support_struct.h"
|
||||||
|
|
||||||
// rcl action specific ret codes in 2XXX
|
// rcl action specific ret codes in 2XXX
|
||||||
/// Action name does not pass validation return code.
|
/// Action name does not pass validation return code.
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
#include "rcl/rcl.h"
|
#include "rcl/rcl.h"
|
||||||
|
|
||||||
#include "rosidl_generator_c/primitives_sequence_functions.h"
|
#include "rosidl_runtime_c/primitives_sequence_functions.h"
|
||||||
|
|
||||||
#include "test_msgs/action/fibonacci.h"
|
#include "test_msgs/action/fibonacci.h"
|
||||||
|
|
||||||
|
@ -448,7 +448,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result
|
||||||
|
|
||||||
// Initialize result response
|
// Initialize result response
|
||||||
ASSERT_TRUE(
|
ASSERT_TRUE(
|
||||||
rosidl_generator_c__int32__Sequence__init(
|
rosidl_runtime_c__int32__Sequence__init(
|
||||||
&outgoing_result_response.result.sequence, 4));
|
&outgoing_result_response.result.sequence, 4));
|
||||||
outgoing_result_response.result.sequence.data[0] = 0;
|
outgoing_result_response.result.sequence.data[0] = 0;
|
||||||
outgoing_result_response.result.sequence.data[1] = 1;
|
outgoing_result_response.result.sequence.data[1] = 1;
|
||||||
|
@ -593,7 +593,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedba
|
||||||
|
|
||||||
// Initialize feedback
|
// Initialize feedback
|
||||||
ASSERT_TRUE(
|
ASSERT_TRUE(
|
||||||
rosidl_generator_c__int32__Sequence__init(
|
rosidl_runtime_c__int32__Sequence__init(
|
||||||
&outgoing_feedback.feedback.sequence, 3));
|
&outgoing_feedback.feedback.sequence, 3));
|
||||||
outgoing_feedback.feedback.sequence.data[0] = 0;
|
outgoing_feedback.feedback.sequence.data[0] = 0;
|
||||||
outgoing_feedback.feedback.sequence.data[1] = 1;
|
outgoing_feedback.feedback.sequence.data[1] = 1;
|
||||||
|
@ -952,7 +952,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu
|
||||||
|
|
||||||
// Initialize result response
|
// Initialize result response
|
||||||
ASSERT_TRUE(
|
ASSERT_TRUE(
|
||||||
rosidl_generator_c__int32__Sequence__init(
|
rosidl_runtime_c__int32__Sequence__init(
|
||||||
&outgoing_result_response.result.sequence, 4));
|
&outgoing_result_response.result.sequence, 4));
|
||||||
outgoing_result_response.result.sequence.data[0] = 0;
|
outgoing_result_response.result.sequence.data[0] = 0;
|
||||||
outgoing_result_response.result.sequence.data[1] = 1;
|
outgoing_result_response.result.sequence.data[1] = 1;
|
||||||
|
@ -1015,7 +1015,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feed
|
||||||
|
|
||||||
// Initialize feedback
|
// Initialize feedback
|
||||||
ASSERT_TRUE(
|
ASSERT_TRUE(
|
||||||
rosidl_generator_c__int32__Sequence__init(
|
rosidl_runtime_c__int32__Sequence__init(
|
||||||
&outgoing_feedback.feedback.sequence, 3));
|
&outgoing_feedback.feedback.sequence, 3));
|
||||||
outgoing_feedback.feedback.sequence.data[0] = 0;
|
outgoing_feedback.feedback.sequence.data[0] = 0;
|
||||||
outgoing_feedback.feedback.sequence.data[1] = 1;
|
outgoing_feedback.feedback.sequence.data[1] = 1;
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
#include "rcl/rcl.h"
|
#include "rcl/rcl.h"
|
||||||
|
|
||||||
#include "rosidl_generator_c/primitives_sequence_functions.h"
|
#include "rosidl_runtime_c/primitives_sequence_functions.h"
|
||||||
|
|
||||||
#include "test_msgs/action/fibonacci.h"
|
#include "test_msgs/action/fibonacci.h"
|
||||||
|
|
||||||
|
@ -307,7 +307,7 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in
|
||||||
|
|
||||||
// Initialize feedback
|
// Initialize feedback
|
||||||
ASSERT_TRUE(
|
ASSERT_TRUE(
|
||||||
rosidl_generator_c__int32__Sequence__init(
|
rosidl_runtime_c__int32__Sequence__init(
|
||||||
&this->outgoing_feedback.feedback.sequence, 3));
|
&this->outgoing_feedback.feedback.sequence, 3));
|
||||||
this->outgoing_feedback.feedback.sequence.data[0] = 0;
|
this->outgoing_feedback.feedback.sequence.data[0] = 0;
|
||||||
this->outgoing_feedback.feedback.sequence.data[1] = 1;
|
this->outgoing_feedback.feedback.sequence.data[1] = 1;
|
||||||
|
@ -398,7 +398,7 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in
|
||||||
|
|
||||||
// Initialize result response
|
// Initialize result response
|
||||||
ASSERT_TRUE(
|
ASSERT_TRUE(
|
||||||
rosidl_generator_c__int32__Sequence__init(
|
rosidl_runtime_c__int32__Sequence__init(
|
||||||
&this->outgoing_result_response.result.sequence, 4));
|
&this->outgoing_result_response.result.sequence, 4));
|
||||||
this->outgoing_result_response.result.sequence.data[0] = 0;
|
this->outgoing_result_response.result.sequence.data[0] = 0;
|
||||||
this->outgoing_result_response.result.sequence.data[1] = 1;
|
this->outgoing_result_response.result.sequence.data[1] = 1;
|
||||||
|
@ -575,7 +575,7 @@ TEST_F(
|
||||||
|
|
||||||
// Initialize feedback
|
// Initialize feedback
|
||||||
ASSERT_TRUE(
|
ASSERT_TRUE(
|
||||||
rosidl_generator_c__int32__Sequence__init(
|
rosidl_runtime_c__int32__Sequence__init(
|
||||||
&this->outgoing_feedback.feedback.sequence, 3));
|
&this->outgoing_feedback.feedback.sequence, 3));
|
||||||
this->outgoing_feedback.feedback.sequence.data[0] = 0;
|
this->outgoing_feedback.feedback.sequence.data[0] = 0;
|
||||||
this->outgoing_feedback.feedback.sequence.data[1] = 1;
|
this->outgoing_feedback.feedback.sequence.data[1] = 1;
|
||||||
|
@ -666,7 +666,7 @@ TEST_F(
|
||||||
|
|
||||||
// Initialize result response
|
// Initialize result response
|
||||||
ASSERT_TRUE(
|
ASSERT_TRUE(
|
||||||
rosidl_generator_c__int32__Sequence__init(
|
rosidl_runtime_c__int32__Sequence__init(
|
||||||
&this->outgoing_result_response.result.sequence, 4));
|
&this->outgoing_result_response.result.sequence, 4));
|
||||||
this->outgoing_result_response.result.sequence.data[0] = 0;
|
this->outgoing_result_response.result.sequence.data[0] = 0;
|
||||||
this->outgoing_result_response.result.sequence.data[1] = 1;
|
this->outgoing_result_response.result.sequence.data[1] = 1;
|
||||||
|
|
|
@ -31,8 +31,8 @@ extern "C"
|
||||||
|
|
||||||
#include "rmw/validate_full_topic_name.h"
|
#include "rmw/validate_full_topic_name.h"
|
||||||
|
|
||||||
#include "rosidl_generator_c/message_type_support_struct.h"
|
#include "rosidl_runtime_c/message_type_support_struct.h"
|
||||||
#include "rosidl_generator_c/string_functions.h"
|
#include "rosidl_runtime_c/string_functions.h"
|
||||||
|
|
||||||
#include "rcl_lifecycle/data_types.h"
|
#include "rcl_lifecycle/data_types.h"
|
||||||
|
|
||||||
|
@ -251,9 +251,9 @@ rcl_lifecycle_com_interface_publish_notification(
|
||||||
const rcl_lifecycle_state_t * start, const rcl_lifecycle_state_t * goal)
|
const rcl_lifecycle_state_t * start, const rcl_lifecycle_state_t * goal)
|
||||||
{
|
{
|
||||||
msg.start_state.id = start->id;
|
msg.start_state.id = start->id;
|
||||||
rosidl_generator_c__String__assign(&msg.start_state.label, start->label);
|
rosidl_runtime_c__String__assign(&msg.start_state.label, start->label);
|
||||||
msg.goal_state.id = goal->id;
|
msg.goal_state.id = goal->id;
|
||||||
rosidl_generator_c__String__assign(&msg.goal_state.label, goal->label);
|
rosidl_runtime_c__String__assign(&msg.goal_state.label, goal->label);
|
||||||
|
|
||||||
return rcl_publish(&com_interface->pub_transition_event, &msg, NULL);
|
return rcl_publish(&com_interface->pub_transition_event, &msg, NULL);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue