From 2d54fe3e620660eb1595707d3b65af9b3a9fcb1b Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Fri, 8 Jun 2018 16:08:08 +0200 Subject: [PATCH] add test for set parameters atomically --- test_rclcpp/test/parameter_fixtures.hpp | 20 ++++++++++++++++++++ test_rclcpp/test/test_remote_parameters.cpp | 16 ++++++++++++++++ 2 files changed, 36 insertions(+) diff --git a/test_rclcpp/test/parameter_fixtures.hpp b/test_rclcpp/test/parameter_fixtures.hpp index 8fa14c2b..23493ef3 100644 --- a/test_rclcpp/test/parameter_fixtures.hpp +++ b/test_rclcpp/test/parameter_fixtures.hpp @@ -50,6 +50,26 @@ void set_test_parameters( } } +void set_test_parameters_atomically( + std::shared_ptr parameters_client) +{ + printf("Setting parameters atomically\n"); + // Set several differnet types of parameters. + auto set_parameters_result = parameters_client->set_parameters_atomically({ + rclcpp::Parameter("foo", 2), + rclcpp::Parameter("bar", "hello"), + rclcpp::Parameter("barstr", std::string("hello_str")), + rclcpp::Parameter("baz", 1.45), + rclcpp::Parameter("foo.first", 8), + rclcpp::Parameter("foo.second", 42), + rclcpp::Parameter("foobar", true), + }); + printf("Got set_parameters_atomically result\n"); + + // Check to see if they were set. + ASSERT_TRUE(set_parameters_result.successful); +} + void verify_set_parameters_async( std::shared_ptr node, std::shared_ptr parameters_client) diff --git a/test_rclcpp/test/test_remote_parameters.cpp b/test_rclcpp/test/test_remote_parameters.cpp index e03d2228..f02fab20 100644 --- a/test_rclcpp/test/test_remote_parameters.cpp +++ b/test_rclcpp/test/test_remote_parameters.cpp @@ -67,6 +67,22 @@ TEST(CLASSNAME(parameters, rmw_implementation), test_remote_parameters_sync) { verify_test_parameters(parameters_client); } +TEST(CLASSNAME(parameters, rmw_implementation), test_set_remote_parameters_atomically_sync) { + std::string test_server_name = "test_parameters_server"; + + auto node = rclcpp::Node::make_shared(std::string("test_set_remote_parameters_atomically_sync")); + + auto parameters_client = std::make_shared(node, + test_server_name); + if (!parameters_client->wait_for_service(20s)) { + ASSERT_TRUE(false) << "service not available after waiting"; + } + + set_test_parameters_atomically(parameters_client); + + verify_test_parameters(parameters_client); +} + int main(int argc, char ** argv) { rclcpp::init(argc, argv);