diff --git a/test_cli/test/initial_params.cpp b/test_cli/test/initial_params.cpp index 7a2c5694..31cb25a2 100644 --- a/test_cli/test/initial_params.cpp +++ b/test_cli/test/initial_params.cpp @@ -22,7 +22,9 @@ int main(int argc, char ** argv) std::string node_name = "initial_params_node"; std::string namespace_ = "/"; - auto node = rclcpp::Node::make_shared(node_name, namespace_); + rclcpp::NodeOptions options; + options.automatically_declare_initial_parameters(true); + auto node = rclcpp::Node::make_shared(node_name, namespace_, options); rclcpp::spin(node); diff --git a/test_rclcpp/test/parameter_fixtures.hpp b/test_rclcpp/test/parameter_fixtures.hpp index 23493ef3..ba32c424 100644 --- a/test_rclcpp/test/parameter_fixtures.hpp +++ b/test_rclcpp/test/parameter_fixtures.hpp @@ -27,6 +27,17 @@ const double test_epsilon = 1e-6; +void declare_test_parameters(std::shared_ptr node) +{ + node->declare_parameter("foo"); + node->declare_parameter("bar"); + node->declare_parameter("barstr"); + node->declare_parameter("baz"); + node->declare_parameter("foo.first"); + node->declare_parameter("foo.second"); + node->declare_parameter("foobar"); +} + void set_test_parameters( std::shared_ptr parameters_client) { @@ -167,7 +178,7 @@ void verify_test_parameters( parameters_and_prefixes = parameters_client->list_parameters({}, rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE); std::vector all_names = { - "foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar" + "foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar", "use_sim_time" }; EXPECT_EQ(parameters_and_prefixes.names.size(), all_names.size()); for (auto & name : all_names) { @@ -190,9 +201,9 @@ void verify_test_parameters( } printf("Listing parameters with depth 1\n"); // List most of the parameters, using an empty prefix list and depth=1 - parameters_and_prefixes = parameters_client->list_parameters({}, 1); + parameters_and_prefixes = parameters_client->list_parameters({}, 1u); std::vector depth_one_names = { - "foo", "bar", "barstr", "baz", "foobar" + "foo", "bar", "barstr", "baz", "foobar", "use_sim_time" }; EXPECT_EQ(parameters_and_prefixes.names.size(), depth_one_names.size()); for (auto & name : depth_one_names) { @@ -290,7 +301,7 @@ void verify_get_parameters_async( rclcpp::spin_until_future_complete(node, result5); parameters_and_prefixes = result5.get(); std::vector all_names = { - "foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar" + "foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar", "use_sim_time" }; EXPECT_EQ(parameters_and_prefixes.names.size(), all_names.size()); for (auto & name : all_names) { diff --git a/test_rclcpp/test/test_local_parameters.cpp b/test_rclcpp/test/test_local_parameters.cpp index 1dd39f6c..d99cdc3e 100644 --- a/test_rclcpp/test/test_local_parameters.cpp +++ b/test_rclcpp/test/test_local_parameters.cpp @@ -68,6 +68,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) { TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) { if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous"); + declare_test_parameters(node); auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; @@ -79,6 +80,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) { TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_repeated) { if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous_repeated"); + declare_test_parameters(node); auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; @@ -93,6 +95,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_rep TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_asynchronous) { if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared(std::string("test_parameters_local_asynchronous")); + declare_test_parameters(node); auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; @@ -107,6 +110,13 @@ class ParametersAsyncNode : public rclcpp::Node ParametersAsyncNode() : Node("test_local_parameters_async_with_callback") { + this->declare_parameter("foo"); + this->declare_parameter("bar"); + this->declare_parameter("barstr"); + this->declare_parameter("baz"); + this->declare_parameter("foobar"); + this->declare_parameter("barfoo"); + parameters_client_ = std::make_shared(this); } @@ -157,6 +167,13 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_call TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) { if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); + node->declare_parameter("foo"); + node->declare_parameter("bar"); + node->declare_parameter("barstr"); + node->declare_parameter("baz"); + node->declare_parameter("foobar"); + node->declare_parameter("barfoo"); + auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; @@ -267,6 +284,13 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) { TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primitive_type) { if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); + node->declare_parameter("foo"); + node->declare_parameter("bar"); + node->declare_parameter("barstr"); + node->declare_parameter("baz"); + node->declare_parameter("foobar"); + node->declare_parameter("barfoo"); + auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; @@ -333,6 +357,13 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant using rclcpp::Parameter; auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); + node->declare_parameter("foo"); + node->declare_parameter("bar"); + node->declare_parameter("barstr"); + node->declare_parameter("baz"); + node->declare_parameter("foobar"); + node->declare_parameter("barfoo"); + auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; @@ -370,8 +401,9 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant EXPECT_FALSE(got_param); // Throw on non-existent param for returning version - EXPECT_THROW(node->get_parameter("no_such_param"), std::out_of_range); - + EXPECT_THROW( + node->get_parameter("no_such_param"), + rclcpp::exceptions::ParameterNotDeclaredException); EXPECT_NO_THROW(got_param = node->get_parameter("bar", bar)); EXPECT_EQ(true, got_param); @@ -386,68 +418,49 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant EXPECT_EQ(true, got_param); } -TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_parameter_or) { - if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} - using rclcpp::Parameter; - - auto node = rclcpp::Node::make_shared("test_parameters_get_parameter_or"); - auto set_parameters_results = node->set_parameters({ - Parameter("foo", 2), - }); - printf("Got set_parameters result\n"); - - // Check to see if they were set. - for (auto & result : set_parameters_results) { - ASSERT_TRUE(result.successful); - } - - { - // try to get with default a parameter that is already set - int64_t foo_value = -1; - node->get_parameter_or("foo", foo_value, static_cast(42)); - ASSERT_EQ(foo_value, 2); - int64_t foo_value2 = -1; - ASSERT_TRUE(node->get_parameter("foo", foo_value2)); - ASSERT_EQ(foo_value2, 2); - } - - { - // try to get with default a parameter that is not set - int64_t bar_value = -1; - node->get_parameter_or("bar", bar_value, static_cast(42)); - ASSERT_EQ(bar_value, 42); - // ensure it is still unset - int64_t bar_value2 = -1; - ASSERT_FALSE(node->get_parameter("bar", bar_value2)); - ASSERT_EQ(bar_value2, -1); - } -} - TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_parameter_or_set) { if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} using rclcpp::Parameter; auto node = rclcpp::Node::make_shared("test_parameters_get_parameter_or_set_default"); - auto set_parameters_results = node->set_parameters({ - Parameter("foo", 2), - }); - - // Check to see if they were set. - for (auto & result : set_parameters_results) { - ASSERT_TRUE(result.successful); - } + node->declare_parameter("foo", 2); + node->declare_parameter("bar"); { // try to get with default a parameter that is already set int64_t foo_value = -1; +#if !defined(_WIN32) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#else // !defined(_WIN32) +# pragma warning(push) +# pragma warning(disable: 4996) +#endif node->get_parameter_or_set("foo", foo_value, static_cast(42)); +#if !defined(_WIN32) +# pragma GCC diagnostic pop +#else // !defined(_WIN32) +# pragma warning(pop) +#endif ASSERT_EQ(foo_value, 2); } { // try to get with default a parameter that is not set int64_t bar_value = -1; +#if !defined(_WIN32) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#else // !defined(_WIN32) +# pragma warning(push) +# pragma warning(disable: 4996) +#endif node->get_parameter_or_set("bar", bar_value, static_cast(42)); +#if !defined(_WIN32) +# pragma GCC diagnostic pop +#else // !defined(_WIN32) +# pragma warning(pop) +#endif ASSERT_EQ(bar_value, 42); // ensure it is now set int64_t bar_value2 = -1; @@ -461,6 +474,9 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), set_parameter_if_not_ using rclcpp::Parameter; auto node = rclcpp::Node::make_shared("test_parameters_set_parameter_if_not_set"); + node->declare_parameter("foo"); + node->declare_parameter("bar"); + auto set_parameters_results = node->set_parameters({ Parameter("foo", 2), }); @@ -473,7 +489,19 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), set_parameter_if_not_ { // try to set_if_not_set a parameter that is already set +#if !defined(_WIN32) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#else // !defined(_WIN32) +# pragma warning(push) +# pragma warning(disable: 4996) +#endif node->set_parameter_if_not_set("foo", 42); +#if !defined(_WIN32) +# pragma GCC diagnostic pop +#else // !defined(_WIN32) +# pragma warning(pop) +#endif // make sure it did not change (it was already set) int64_t foo_value = -1; ASSERT_TRUE(node->get_parameter("foo", foo_value)); @@ -482,7 +510,19 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), set_parameter_if_not_ { // try to get with default a parameter that is not set +#if !defined(_WIN32) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#else // !defined(_WIN32) +# pragma warning(push) +# pragma warning(disable: 4996) +#endif node->set_parameter_if_not_set("bar", 42); +#if !defined(_WIN32) +# pragma GCC diagnostic pop +#else // !defined(_WIN32) +# pragma warning(pop) +#endif // ensure it was set int64_t bar_value = -1; ASSERT_TRUE(node->get_parameter("bar", bar_value)); diff --git a/test_rclcpp/test/test_parameters_server.cpp b/test_rclcpp/test/test_parameters_server.cpp index b1270ce7..982e92e7 100644 --- a/test_rclcpp/test/test_parameters_server.cpp +++ b/test_rclcpp/test/test_parameters_server.cpp @@ -12,23 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include -#include -#include -#include - #include "rclcpp/rclcpp.hpp" - int main(int argc, char ** argv) { rclcpp::init(argc, argv); - auto node = rclcpp::Node::make_shared(std::string("test_parameters_server")); + auto node = rclcpp::Node::make_shared( + "test_parameters_server", + "/", + rclcpp::NodeOptions().allow_undeclared_parameters(true)); rclcpp::spin(node); - rclcpp::shutdown(); return 0; }