Skip to content

Commit

Permalink
Add tests for node_options API (#1343)
Browse files Browse the repository at this point in the history
* Add tests for node_options API

Signed-off-by: Stephen Brawner <brawner@gmail.com>

* Remove c-style casts

Signed-off-by: Stephen Brawner <brawner@gmail.com>
  • Loading branch information
brawner committed Sep 29, 2020
1 parent 554d933 commit a9add88
Show file tree
Hide file tree
Showing 2 changed files with 110 additions and 1 deletion.
2 changes: 1 addition & 1 deletion rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,7 @@ endif()
ament_add_gtest(test_node_options rclcpp/test_node_options.cpp)
if(TARGET test_node_options)
ament_target_dependencies(test_node_options "rcl")
target_link_libraries(test_node_options ${PROJECT_NAME})
target_link_libraries(test_node_options ${PROJECT_NAME} mimick)
endif()
ament_add_gtest(test_init_options rclcpp/test_init_options.cpp)
if(TARGET test_init_options)
Expand Down
109 changes: 109 additions & 0 deletions rclcpp/test/rclcpp/test_node_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <gtest/gtest.h>

#include <memory>
#include <string>
#include <vector>

Expand All @@ -23,6 +24,8 @@

#include "rclcpp/node_options.hpp"

#include "../mocking_utils/patch.hpp"


TEST(TestNodeOptions, ros_args_only) {
rcl_allocator_t allocator = rcl_get_default_allocator();
Expand Down Expand Up @@ -207,3 +210,109 @@ TEST(TestNodeOptions, append_parameter_override) {
EXPECT_EQ(1u, options.parameter_overrides().size());
EXPECT_EQ(std::string("some_parameter"), options.parameter_overrides()[0].get_name());
}

TEST(TestNodeOptions, rcl_node_options_fini_error) {
auto mock = mocking_utils::inject_on_return("lib:rclcpp", rcl_node_options_fini, RCL_RET_ERROR);
auto options = std::make_shared<rclcpp::NodeOptions>();
// Necessary to setup internal pointer
ASSERT_NE(nullptr, options->get_rcl_node_options());
// If fini fails, this should just log an error and continue
EXPECT_NO_THROW(options.reset());
}

TEST(TestNodeOptions, bool_setters_and_getters) {
rclcpp::NodeOptions options;

options.use_global_arguments(false);
EXPECT_FALSE(options.use_global_arguments());
EXPECT_FALSE(options.get_rcl_node_options()->use_global_arguments);
options.use_global_arguments(true);
EXPECT_TRUE(options.use_global_arguments());
EXPECT_TRUE(options.get_rcl_node_options()->use_global_arguments);

options.enable_rosout(false);
EXPECT_FALSE(options.enable_rosout());
EXPECT_FALSE(options.get_rcl_node_options()->enable_rosout);
options.enable_rosout(true);
EXPECT_TRUE(options.enable_rosout());
EXPECT_TRUE(options.get_rcl_node_options()->enable_rosout);

options.use_intra_process_comms(false);
EXPECT_FALSE(options.use_intra_process_comms());
options.use_intra_process_comms(true);
EXPECT_TRUE(options.use_intra_process_comms());

options.enable_topic_statistics(false);
EXPECT_FALSE(options.enable_topic_statistics());
options.enable_topic_statistics(true);
EXPECT_TRUE(options.enable_topic_statistics());

options.start_parameter_services(false);
EXPECT_FALSE(options.start_parameter_services());
options.start_parameter_services(true);
EXPECT_TRUE(options.start_parameter_services());

options.allow_undeclared_parameters(false);
EXPECT_FALSE(options.allow_undeclared_parameters());
options.allow_undeclared_parameters(true);
EXPECT_TRUE(options.allow_undeclared_parameters());

options.start_parameter_event_publisher(false);
EXPECT_FALSE(options.start_parameter_event_publisher());
options.start_parameter_event_publisher(true);
EXPECT_TRUE(options.start_parameter_event_publisher());

options.automatically_declare_parameters_from_overrides(false);
EXPECT_FALSE(options.automatically_declare_parameters_from_overrides());
options.automatically_declare_parameters_from_overrides(true);
EXPECT_TRUE(options.automatically_declare_parameters_from_overrides());
}

TEST(TestNodeOptions, parameter_event_qos) {
rclcpp::NodeOptions options;
rclcpp::QoS qos1(1);
rclcpp::QoS qos2(2);
EXPECT_NE(qos1, options.parameter_event_qos());
EXPECT_NE(qos2, options.parameter_event_qos());
options.parameter_event_qos(qos1);
EXPECT_EQ(qos1, options.parameter_event_qos());
options.parameter_event_qos(qos2);
EXPECT_EQ(qos2, options.parameter_event_qos());
}

TEST(TestNodeOptions, parameter_event_publisher_options) {
rclcpp::NodeOptions options;
rclcpp::PublisherOptionsBase publisher_options;
publisher_options.use_default_callbacks = true;
options.parameter_event_publisher_options(publisher_options);
EXPECT_TRUE(options.parameter_event_publisher_options().use_default_callbacks);

publisher_options.use_default_callbacks = false;
options.parameter_event_publisher_options(publisher_options);
EXPECT_FALSE(options.parameter_event_publisher_options().use_default_callbacks);
}

TEST(TestNodeOptions, set_get_allocator) {
rclcpp::NodeOptions options;
EXPECT_NE(nullptr, options.allocator().allocate);
EXPECT_NE(nullptr, options.allocator().deallocate);
EXPECT_NE(nullptr, options.allocator().reallocate);
EXPECT_NE(nullptr, options.allocator().zero_allocate);

rcl_allocator_t fake_allocator;
fake_allocator.allocate = [](size_t, void *) -> void * {return nullptr;};
fake_allocator.deallocate = [](void *, void *) {};
fake_allocator.reallocate = [](void *, size_t, void *) -> void * {return nullptr;};
fake_allocator.zero_allocate = [](size_t, size_t, void *) -> void * {return nullptr;};
fake_allocator.state = rcl_get_default_allocator().state;

options.allocator(fake_allocator);
EXPECT_EQ(fake_allocator.allocate, options.allocator().allocate);
EXPECT_EQ(fake_allocator.deallocate, options.allocator().deallocate);
EXPECT_EQ(fake_allocator.reallocate, options.allocator().reallocate);
EXPECT_EQ(fake_allocator.zero_allocate, options.allocator().zero_allocate);
EXPECT_EQ(fake_allocator.state, options.allocator().state);

// Check invalid allocator
EXPECT_THROW(options.get_rcl_node_options(), std::bad_alloc);
}

0 comments on commit a9add88

Please sign in to comment.