Skip to content

Commit

Permalink
Add more test cases for different NodeOptions
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Jan 18, 2024
1 parent d95e914 commit a4d9fd9
Show file tree
Hide file tree
Showing 3 changed files with 102 additions and 1 deletion.
2 changes: 2 additions & 0 deletions controller_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@ if(BUILD_TESTING)
)

ament_add_gmock(test_controller_with_options test/test_controller_with_options.cpp)
install(FILES test/test_controller_node_options.yaml
DESTINATION test)
target_link_libraries(test_controller_with_options
controller_interface
)
Expand Down
6 changes: 6 additions & 0 deletions controller_interface/test/test_controller_node_options.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
controller_name:
ros__parameters:
parameter_list:
parameter1: 20.0
parameter2: 23.14
parameter3: -52.323
95 changes: 94 additions & 1 deletion controller_interface/test/test_controller_with_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#include "test_controller_with_options.hpp"

#include <gtest/gtest.h>
#include <ament_index_cpp/get_package_prefix.hpp>
#include <string>

#include "rclcpp/rclcpp.hpp"

class FriendControllerWithOptions : public controller_with_options::ControllerWithOptions
Expand Down Expand Up @@ -49,6 +49,34 @@ TEST(ControllerWithOption, init_with_overrides)
const auto & node_options = controller.get_node()->get_node_options();
EXPECT_TRUE(node_options.allow_undeclared_parameters());
EXPECT_TRUE(node_options.automatically_declare_parameters_from_overrides());
EXPECT_TRUE(node_options.arguments().empty());
// checks that the parameters have been correctly processed
EXPECT_EQ(controller.params.size(), 3u);
EXPECT_EQ(controller.params["parameter1"], 1.);
EXPECT_EQ(controller.params["parameter2"], 2.);
EXPECT_EQ(controller.params["parameter3"], 3.);
rclcpp::shutdown();
}

TEST(ControllerWithOption, init_with_node_options_arguments_parameters)
{
char const * const argv[] = {""};
int argc = arrlen(argv);
rclcpp::init(argc, argv);
// creates the controller
FriendControllerWithOptions controller;
auto controller_node_options = controller.define_custom_node_options();
controller_node_options.arguments(
{"--ros-args", "-p", "parameter_list.parameter1:=1.", "-p", "parameter_list.parameter2:=2.",
"-p", "parameter_list.parameter3:=3."});
EXPECT_EQ(
controller.init("controller_name", "", 50.0, "", controller_node_options),
controller_interface::return_type::OK);
// checks that the node options have been updated
const auto & node_options = controller.get_node()->get_node_options();
EXPECT_TRUE(node_options.allow_undeclared_parameters());
EXPECT_TRUE(node_options.automatically_declare_parameters_from_overrides());
EXPECT_EQ(7lu, node_options.arguments().size());
// checks that the parameters have been correctly processed
EXPECT_EQ(controller.params.size(), 3u);
EXPECT_EQ(controller.params["parameter1"], 1.);
Expand All @@ -57,6 +85,71 @@ TEST(ControllerWithOption, init_with_overrides)
rclcpp::shutdown();
}

TEST(ControllerWithOption, init_with_node_options_arguments_parameters_file)
{
char const * const argv[] = {""};
int argc = arrlen(argv);
rclcpp::init(argc, argv);
// creates the controller
FriendControllerWithOptions controller;
const std::string params_file_path = ament_index_cpp::get_package_prefix("controller_interface") +
"/test/test_controller_node_options.yaml";
std::cerr << params_file_path << std::endl;
auto controller_node_options = controller.define_custom_node_options();
controller_node_options.arguments({"--ros-args", "--params-file", params_file_path});
EXPECT_EQ(
controller.init("controller_name", "", 50.0, "", controller_node_options),
controller_interface::return_type::OK);
// checks that the node options have been updated
const auto & node_options = controller.get_node()->get_node_options();
EXPECT_TRUE(node_options.allow_undeclared_parameters());
EXPECT_TRUE(node_options.automatically_declare_parameters_from_overrides());
EXPECT_EQ(3lu, node_options.arguments().size());
// checks that the parameters have been correctly processed
EXPECT_EQ(controller.params.size(), 3u);
EXPECT_EQ(controller.params["parameter1"], 20.0);
EXPECT_EQ(controller.params["parameter2"], 23.14);
EXPECT_EQ(controller.params["parameter3"], -52.323);
bool use_sim_time(true);
controller.get_node()->get_parameter_or("use_sim_time", use_sim_time, false);
ASSERT_FALSE(use_sim_time);
rclcpp::shutdown();
}

TEST(
ControllerWithOption, init_with_node_options_arguments_parameters_file_and_override_command_line)
{
char const * const argv[] = {""};
int argc = arrlen(argv);
rclcpp::init(argc, argv);
// creates the controller
FriendControllerWithOptions controller;
const std::string params_file_path = ament_index_cpp::get_package_prefix("controller_interface") +
"/test/test_controller_node_options.yaml";
std::cerr << params_file_path << std::endl;
auto controller_node_options = controller.define_custom_node_options();
controller_node_options.arguments(
{"--ros-args", "--params-file", params_file_path, "-p", "parameter_list.parameter1:=562.785",
"-p", "use_sim_time:=true"});
EXPECT_EQ(
controller.init("controller_name", "", 50.0, "", controller_node_options),
controller_interface::return_type::OK);
// checks that the node options have been updated
const auto & node_options = controller.get_node()->get_node_options();
EXPECT_TRUE(node_options.allow_undeclared_parameters());
EXPECT_TRUE(node_options.automatically_declare_parameters_from_overrides());
EXPECT_EQ(7lu, node_options.arguments().size());
// checks that the parameters have been correctly processed
EXPECT_EQ(controller.params.size(), 3u);
EXPECT_EQ(controller.params["parameter1"], 562.785);
EXPECT_EQ(controller.params["parameter2"], 23.14);
EXPECT_EQ(controller.params["parameter3"], -52.323);
bool use_sim_time(false);
controller.get_node()->get_parameter_or("use_sim_time", use_sim_time, false);
ASSERT_TRUE(use_sim_time);
rclcpp::shutdown();
}

TEST(ControllerWithOption, init_without_overrides)
{
// mocks the declaration of overrides parameters in a yaml file
Expand Down

0 comments on commit a4d9fd9

Please sign in to comment.