use test_msgs instead of std_msgs in tests (#270)
This commit is contained in:
parent
c21a250a06
commit
d3a734f266
6 changed files with 75 additions and 85 deletions
|
@ -35,7 +35,6 @@
|
||||||
<test_depend>rmw_implementation_cmake</test_depend>
|
<test_depend>rmw_implementation_cmake</test_depend>
|
||||||
<test_depend>launch</test_depend>
|
<test_depend>launch</test_depend>
|
||||||
<test_depend>osrf_testing_tools_cpp</test_depend>
|
<test_depend>osrf_testing_tools_cpp</test_depend>
|
||||||
<test_depend>std_msgs</test_depend>
|
|
||||||
<test_depend>test_msgs</test_depend>
|
<test_depend>test_msgs</test_depend>
|
||||||
|
|
||||||
<export>
|
<export>
|
||||||
|
|
|
@ -1,7 +1,6 @@
|
||||||
find_package(ament_cmake_gtest REQUIRED)
|
find_package(ament_cmake_gtest REQUIRED)
|
||||||
find_package(ament_cmake_pytest REQUIRED)
|
find_package(ament_cmake_pytest REQUIRED)
|
||||||
|
|
||||||
find_package(std_msgs REQUIRED)
|
|
||||||
find_package(test_msgs REQUIRED)
|
find_package(test_msgs REQUIRED)
|
||||||
|
|
||||||
find_package(rmw_implementation_cmake REQUIRED)
|
find_package(rmw_implementation_cmake REQUIRED)
|
||||||
|
@ -99,7 +98,7 @@ function(test_target_function)
|
||||||
ENV ${rmw_implementation_env_var}
|
ENV ${rmw_implementation_env_var}
|
||||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||||
LIBRARIES ${PROJECT_NAME}
|
LIBRARIES ${PROJECT_NAME}
|
||||||
AMENT_DEPENDENCIES ${rmw_implementation} "std_msgs" "test_msgs"
|
AMENT_DEPENDENCIES ${rmw_implementation} "test_msgs"
|
||||||
${SKIP_TEST}
|
${SKIP_TEST}
|
||||||
)
|
)
|
||||||
|
|
||||||
|
@ -142,7 +141,7 @@ function(test_target_function)
|
||||||
ENV ${rmw_implementation_env_var}
|
ENV ${rmw_implementation_env_var}
|
||||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||||
LIBRARIES ${PROJECT_NAME}
|
LIBRARIES ${PROJECT_NAME}
|
||||||
AMENT_DEPENDENCIES "std_msgs" "test_msgs"
|
AMENT_DEPENDENCIES "test_msgs"
|
||||||
)
|
)
|
||||||
|
|
||||||
rcl_add_custom_gtest(test_guard_condition${target_suffix}
|
rcl_add_custom_gtest(test_guard_condition${target_suffix}
|
||||||
|
@ -160,7 +159,7 @@ function(test_target_function)
|
||||||
ENV ${rmw_implementation_env_var}
|
ENV ${rmw_implementation_env_var}
|
||||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||||
LIBRARIES ${PROJECT_NAME}
|
LIBRARIES ${PROJECT_NAME}
|
||||||
AMENT_DEPENDENCIES ${rmw_implementation} "std_msgs"
|
AMENT_DEPENDENCIES ${rmw_implementation} "test_msgs"
|
||||||
)
|
)
|
||||||
|
|
||||||
rcl_add_custom_gtest(test_service${target_suffix}
|
rcl_add_custom_gtest(test_service${target_suffix}
|
||||||
|
@ -178,7 +177,7 @@ function(test_target_function)
|
||||||
ENV ${rmw_implementation_env_var}
|
ENV ${rmw_implementation_env_var}
|
||||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||||
LIBRARIES ${PROJECT_NAME}
|
LIBRARIES ${PROJECT_NAME}
|
||||||
AMENT_DEPENDENCIES ${rmw_implementation} "std_msgs"
|
AMENT_DEPENDENCIES ${rmw_implementation} "test_msgs"
|
||||||
)
|
)
|
||||||
|
|
||||||
rcl_add_custom_gtest(test_wait${target_suffix}
|
rcl_add_custom_gtest(test_wait${target_suffix}
|
||||||
|
|
|
@ -32,7 +32,7 @@
|
||||||
|
|
||||||
#include "rcutils/logging_macros.h"
|
#include "rcutils/logging_macros.h"
|
||||||
|
|
||||||
#include "std_msgs/msg/string.h"
|
#include "test_msgs/msg/primitives.h"
|
||||||
#include "test_msgs/srv/primitives.h"
|
#include "test_msgs/srv/primitives.h"
|
||||||
|
|
||||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||||
|
@ -333,7 +333,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functio
|
||||||
// Now create a publisher on "topic_name" and check that it is seen.
|
// Now create a publisher on "topic_name" and check that it is seen.
|
||||||
rcl_publisher_t pub = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t pub = rcl_get_zero_initialized_publisher();
|
||||||
rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options();
|
rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options();
|
||||||
auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
ret = rcl_publisher_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_ops);
|
ret = rcl_publisher_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_ops);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
|
@ -410,7 +410,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_guard_conditi
|
||||||
rcl_publisher_t pub = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t pub = rcl_get_zero_initialized_publisher();
|
||||||
rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options();
|
rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options();
|
||||||
rcl_ret_t ret = rcl_publisher_init(
|
rcl_ret_t ret = rcl_publisher_init(
|
||||||
&pub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),
|
&pub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives),
|
||||||
"/chatter_test_graph_guard_condition_topics", &pub_ops);
|
"/chatter_test_graph_guard_condition_topics", &pub_ops);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
// sleep
|
// sleep
|
||||||
|
@ -419,7 +419,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_guard_conditi
|
||||||
rcl_subscription_t sub = rcl_get_zero_initialized_subscription();
|
rcl_subscription_t sub = rcl_get_zero_initialized_subscription();
|
||||||
rcl_subscription_options_t sub_ops = rcl_subscription_get_default_options();
|
rcl_subscription_options_t sub_ops = rcl_subscription_get_default_options();
|
||||||
ret = rcl_subscription_init(
|
ret = rcl_subscription_init(
|
||||||
&sub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),
|
&sub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives),
|
||||||
"/chatter_test_graph_guard_condition_topics", &sub_ops);
|
"/chatter_test_graph_guard_condition_topics", &sub_ops);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
// sleep
|
// sleep
|
||||||
|
|
|
@ -17,8 +17,7 @@
|
||||||
#include "rcl/publisher.h"
|
#include "rcl/publisher.h"
|
||||||
|
|
||||||
#include "rcl/rcl.h"
|
#include "rcl/rcl.h"
|
||||||
#include "std_msgs/msg/int64.h"
|
#include "test_msgs/msg/primitives.h"
|
||||||
#include "std_msgs/msg/string.h"
|
|
||||||
#include "rosidl_generator_c/string_functions.h"
|
#include "rosidl_generator_c/string_functions.h"
|
||||||
|
|
||||||
#include "./failing_allocator_functions.hpp"
|
#include "./failing_allocator_functions.hpp"
|
||||||
|
@ -64,19 +63,10 @@ public:
|
||||||
TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nominal) {
|
TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nominal) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
// TODO(wjwwood): Change this back to just chatter when this OpenSplice problem is resolved:
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
// ========================================================================================
|
const char * topic_name = "chatter";
|
||||||
// Report : WARNING
|
const char * expected_topic_name = "/chatter";
|
||||||
// Date : Wed Feb 10 18:17:03 PST 2016
|
|
||||||
// Description : Create Topic "chatter" failed: typename <std_msgs::msg::dds_::Int64_>
|
|
||||||
// differs exiting definition <std_msgs::msg::dds_::String_>.
|
|
||||||
// Node : farl
|
|
||||||
// Process : test_subscription__rmw_opensplice_cpp <23524>
|
|
||||||
// Thread : main thread 7fff7342d000
|
|
||||||
// Internals : V6.4.140407OSS///v_topicNew/v_topic.c/448/21/1455157023.781423000
|
|
||||||
const char * topic_name = "chatter_int64";
|
|
||||||
const char * expected_topic_name = "/chatter_int64";
|
|
||||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||||
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options);
|
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
|
@ -85,11 +75,11 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
});
|
});
|
||||||
EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0);
|
EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0);
|
||||||
std_msgs__msg__Int64 msg;
|
test_msgs__msg__Primitives msg;
|
||||||
std_msgs__msg__Int64__init(&msg);
|
test_msgs__msg__Primitives__init(&msg);
|
||||||
msg.data = 42;
|
msg.int64_value = 42;
|
||||||
ret = rcl_publish(&publisher, &msg);
|
ret = rcl_publish(&publisher, &msg);
|
||||||
std_msgs__msg__Int64__fini(&msg);
|
test_msgs__msg__Primitives__fini(&msg);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -98,7 +88,8 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
|
||||||
TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nominal_string) {
|
TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nominal_string) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
const char * topic_name = "chatter";
|
const char * topic_name = "chatter";
|
||||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||||
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options);
|
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options);
|
||||||
|
@ -107,11 +98,11 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
|
||||||
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
|
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
});
|
});
|
||||||
std_msgs__msg__String msg;
|
test_msgs__msg__Primitives msg;
|
||||||
std_msgs__msg__String__init(&msg);
|
test_msgs__msg__Primitives__init(&msg);
|
||||||
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.data, "testing"));
|
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, "testing"));
|
||||||
ret = rcl_publish(&publisher, &msg);
|
ret = rcl_publish(&publisher, &msg);
|
||||||
std_msgs__msg__String__fini(&msg);
|
test_msgs__msg__Primitives__fini(&msg);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -124,7 +115,8 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
|
||||||
TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_different_types) {
|
TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_different_types) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
const rosidl_message_type_support_t * ts_int = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts_int =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
const char * topic_name = "basename";
|
const char * topic_name = "basename";
|
||||||
const char * expected_topic_name = "/basename";
|
const char * expected_topic_name = "/basename";
|
||||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||||
|
@ -138,7 +130,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff
|
||||||
|
|
||||||
rcl_publisher_t publisher_in_namespace = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t publisher_in_namespace = rcl_get_zero_initialized_publisher();
|
||||||
const rosidl_message_type_support_t * ts_string = ROSIDL_GET_MSG_TYPE_SUPPORT(
|
const rosidl_message_type_support_t * ts_string = ROSIDL_GET_MSG_TYPE_SUPPORT(
|
||||||
std_msgs, msg, String);
|
test_msgs, msg, Primitives);
|
||||||
topic_name = "namespace/basename";
|
topic_name = "namespace/basename";
|
||||||
expected_topic_name = "/namespace/basename";
|
expected_topic_name = "/namespace/basename";
|
||||||
ret = rcl_publisher_init(
|
ret = rcl_publisher_init(
|
||||||
|
@ -150,16 +142,16 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff
|
||||||
});
|
});
|
||||||
EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher_in_namespace), expected_topic_name), 0);
|
EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher_in_namespace), expected_topic_name), 0);
|
||||||
|
|
||||||
std_msgs__msg__Int64 msg_int;
|
test_msgs__msg__Primitives msg_int;
|
||||||
std_msgs__msg__Int64__init(&msg_int);
|
test_msgs__msg__Primitives__init(&msg_int);
|
||||||
msg_int.data = 42;
|
msg_int.int64_value = 42;
|
||||||
ret = rcl_publish(&publisher, &msg_int);
|
ret = rcl_publish(&publisher, &msg_int);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
std_msgs__msg__Int64__fini(&msg_int);
|
test_msgs__msg__Primitives__fini(&msg_int);
|
||||||
|
|
||||||
std_msgs__msg__String msg_string;
|
test_msgs__msg__Primitives msg_string;
|
||||||
std_msgs__msg__String__init(&msg_string);
|
test_msgs__msg__Primitives__init(&msg_string);
|
||||||
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg_string.data, "testing"));
|
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg_string.string_value, "testing"));
|
||||||
ret = rcl_publish(&publisher_in_namespace, &msg_string);
|
ret = rcl_publish(&publisher_in_namespace, &msg_string);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
}
|
}
|
||||||
|
@ -170,7 +162,8 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
// Setup valid inputs.
|
// Setup valid inputs.
|
||||||
rcl_publisher_t publisher;
|
rcl_publisher_t publisher;
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
const char * topic_name = "chatter";
|
const char * topic_name = "chatter";
|
||||||
rcl_publisher_options_t default_publisher_options = rcl_publisher_get_default_options();
|
rcl_publisher_options_t default_publisher_options = rcl_publisher_get_default_options();
|
||||||
|
|
||||||
|
|
|
@ -18,7 +18,7 @@
|
||||||
#include "rcl/remap.h"
|
#include "rcl/remap.h"
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
|
|
||||||
#include "std_msgs/msg/int64.h"
|
#include "test_msgs/msg/primitives.h"
|
||||||
#include "test_msgs/srv/primitives.h"
|
#include "test_msgs/srv/primitives.h"
|
||||||
|
|
||||||
#include "./arg_macros.hpp"
|
#include "./arg_macros.hpp"
|
||||||
|
@ -62,7 +62,8 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g
|
||||||
EXPECT_STREQ("new_ns.new_name", rcl_node_get_logger_name(&node));
|
EXPECT_STREQ("new_ns.new_name", rcl_node_get_logger_name(&node));
|
||||||
}
|
}
|
||||||
{ // Publisher topic gets remapped
|
{ // Publisher topic gets remapped
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||||
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options);
|
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options);
|
||||||
|
@ -71,7 +72,8 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
|
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
|
||||||
}
|
}
|
||||||
{ // Subscription topic gets remapped
|
{ // Subscription topic gets remapped
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
|
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
|
||||||
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
||||||
rcl_ret_t ret = rcl_subscription_init(
|
rcl_ret_t ret = rcl_subscription_init(
|
||||||
|
@ -128,7 +130,8 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global
|
||||||
EXPECT_STREQ("original_ns.original_name", rcl_node_get_logger_name(&node));
|
EXPECT_STREQ("original_ns.original_name", rcl_node_get_logger_name(&node));
|
||||||
}
|
}
|
||||||
{ // Publisher topic does not get remapped
|
{ // Publisher topic does not get remapped
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||||
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options);
|
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options);
|
||||||
|
@ -137,7 +140,8 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
|
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
|
||||||
}
|
}
|
||||||
{ // Subscription topic does not get remapped
|
{ // Subscription topic does not get remapped
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
|
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
|
||||||
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
||||||
rcl_ret_t ret = rcl_subscription_init(
|
rcl_ret_t ret = rcl_subscription_init(
|
||||||
|
@ -195,7 +199,8 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b
|
||||||
EXPECT_STREQ("local_ns.local_name", rcl_node_get_logger_name(&node));
|
EXPECT_STREQ("local_ns.local_name", rcl_node_get_logger_name(&node));
|
||||||
}
|
}
|
||||||
{ // Publisher topic
|
{ // Publisher topic
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||||
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options);
|
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options);
|
||||||
|
@ -204,7 +209,8 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
|
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
|
||||||
}
|
}
|
||||||
{ // Subscription topic
|
{ // Subscription topic
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
|
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
|
||||||
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
||||||
rcl_ret_t ret = rcl_subscription_init(
|
rcl_ret_t ret = rcl_subscription_init(
|
||||||
|
@ -247,7 +253,8 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ
|
||||||
ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "/foo", &default_options));
|
ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "/foo", &default_options));
|
||||||
|
|
||||||
{ // Publisher topic
|
{ // Publisher topic
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||||
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "bar", &publisher_options);
|
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "bar", &publisher_options);
|
||||||
|
@ -256,7 +263,8 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
|
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
|
||||||
}
|
}
|
||||||
{ // Subscription topic
|
{ // Subscription topic
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
|
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
|
||||||
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
||||||
rcl_ret_t ret = rcl_subscription_init(
|
rcl_ret_t ret = rcl_subscription_init(
|
||||||
|
|
|
@ -21,8 +21,7 @@
|
||||||
#include "rcl/subscription.h"
|
#include "rcl/subscription.h"
|
||||||
|
|
||||||
#include "rcl/rcl.h"
|
#include "rcl/rcl.h"
|
||||||
#include "std_msgs/msg/int64.h"
|
#include "test_msgs/msg/primitives.h"
|
||||||
#include "std_msgs/msg/string.h"
|
|
||||||
#include "rosidl_generator_c/string_functions.h"
|
#include "rosidl_generator_c/string_functions.h"
|
||||||
|
|
||||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||||
|
@ -103,19 +102,10 @@ wait_for_subscription_to_be_ready(
|
||||||
TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_nominal) {
|
TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_nominal) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64);
|
const rosidl_message_type_support_t * ts =
|
||||||
// TODO(wjwwood): Change this back to just chatter when this OpenSplice problem is resolved:
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
// ========================================================================================
|
const char * topic = "chatter";
|
||||||
// Report : WARNING
|
const char * expected_topic = "/chatter";
|
||||||
// Date : Wed Feb 10 18:17:03 PST 2016
|
|
||||||
// Description : Create Topic "chatter" failed: typename <std_msgs::msg::dds_::Int64_>
|
|
||||||
// differs exiting definition <std_msgs::msg::dds_::String_>.
|
|
||||||
// Node : farl
|
|
||||||
// Process : test_subscription__rmw_opensplice_cpp <23524>
|
|
||||||
// Thread : main thread 7fff7342d000
|
|
||||||
// Internals : V6.4.140407OSS///v_topicNew/v_topic.c/448/21/1455157023.781423000
|
|
||||||
const char * topic = "rcl_test_subscription_nominal_chatter_int64";
|
|
||||||
const char * expected_topic = "/rcl_test_subscription_nominal_chatter_int64";
|
|
||||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||||
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options);
|
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
|
@ -154,25 +144,25 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
|
||||||
// until then we will sleep for a short period of time
|
// until then we will sleep for a short period of time
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
|
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
|
||||||
{
|
{
|
||||||
std_msgs__msg__Int64 msg;
|
test_msgs__msg__Primitives msg;
|
||||||
std_msgs__msg__Int64__init(&msg);
|
test_msgs__msg__Primitives__init(&msg);
|
||||||
msg.data = 42;
|
msg.int64_value = 42;
|
||||||
ret = rcl_publish(&publisher, &msg);
|
ret = rcl_publish(&publisher, &msg);
|
||||||
std_msgs__msg__Int64__fini(&msg);
|
test_msgs__msg__Primitives__fini(&msg);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
}
|
}
|
||||||
bool success;
|
bool success;
|
||||||
wait_for_subscription_to_be_ready(&subscription, 10, 100, success);
|
wait_for_subscription_to_be_ready(&subscription, 10, 100, success);
|
||||||
ASSERT_TRUE(success);
|
ASSERT_TRUE(success);
|
||||||
{
|
{
|
||||||
std_msgs__msg__Int64 msg;
|
test_msgs__msg__Primitives msg;
|
||||||
std_msgs__msg__Int64__init(&msg);
|
test_msgs__msg__Primitives__init(&msg);
|
||||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
|
||||||
std_msgs__msg__Int64__fini(&msg);
|
test_msgs__msg__Primitives__fini(&msg);
|
||||||
});
|
});
|
||||||
ret = rcl_take(&subscription, &msg, nullptr);
|
ret = rcl_take(&subscription, &msg, nullptr);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
ASSERT_EQ(42, msg.data);
|
ASSERT_EQ(42, msg.int64_value);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -181,7 +171,8 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
|
||||||
TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_nominal_string) {
|
TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_nominal_string) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
|
const rosidl_message_type_support_t * ts =
|
||||||
|
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
|
||||||
const char * topic = "rcl_test_subscription_nominal_string_chatter";
|
const char * topic = "rcl_test_subscription_nominal_string_chatter";
|
||||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||||
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options);
|
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options);
|
||||||
|
@ -204,24 +195,24 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
|
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
|
||||||
const char * test_string = "testing";
|
const char * test_string = "testing";
|
||||||
{
|
{
|
||||||
std_msgs__msg__String msg;
|
test_msgs__msg__Primitives msg;
|
||||||
std_msgs__msg__String__init(&msg);
|
test_msgs__msg__Primitives__init(&msg);
|
||||||
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.data, test_string));
|
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, test_string));
|
||||||
ret = rcl_publish(&publisher, &msg);
|
ret = rcl_publish(&publisher, &msg);
|
||||||
std_msgs__msg__String__fini(&msg);
|
test_msgs__msg__Primitives__fini(&msg);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
}
|
}
|
||||||
bool success;
|
bool success;
|
||||||
wait_for_subscription_to_be_ready(&subscription, 10, 100, success);
|
wait_for_subscription_to_be_ready(&subscription, 10, 100, success);
|
||||||
ASSERT_TRUE(success);
|
ASSERT_TRUE(success);
|
||||||
{
|
{
|
||||||
std_msgs__msg__String msg;
|
test_msgs__msg__Primitives msg;
|
||||||
std_msgs__msg__String__init(&msg);
|
test_msgs__msg__Primitives__init(&msg);
|
||||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
|
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
|
||||||
std_msgs__msg__String__fini(&msg);
|
test_msgs__msg__Primitives__fini(&msg);
|
||||||
});
|
});
|
||||||
ret = rcl_take(&subscription, &msg, nullptr);
|
ret = rcl_take(&subscription, &msg, nullptr);
|
||||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||||
ASSERT_EQ(std::string(test_string), std::string(msg.data.data, msg.data.size));
|
ASSERT_EQ(std::string(test_string), std::string(msg.string_value.data, msg.string_value.size));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue