Skip to content
Snippets Groups Projects
Commit 453cc146 authored by bpwilcox's avatar bpwilcox
Browse files

add NodeOptions to tests with parameters

parent 7ebb2d9f
No related branches found
No related tags found
No related merge requests found
......@@ -43,6 +43,7 @@
#include "nav2_costmap_2d/inflation_layer.hpp"
#include "nav2_costmap_2d/observation_buffer.hpp"
#include "nav2_costmap_2d/testing_helper.hpp"
#include "nav2_util/node_utils.hpp"
using geometry_msgs::msg::Point;
using nav2_costmap_2d::CellData;
......@@ -60,7 +61,8 @@ class TestNode : public ::testing::Test
public:
TestNode()
{
node_ = rclcpp::Node::make_shared("inflation_test_node");
node_ = rclcpp::Node::make_shared(
"inflation_test_node", nav2_util::get_node_options_default());
// Set cost_scaling_factor parameter to 1.0 for inflation layer
node_->set_parameters({rclcpp::Parameter("inflation.cost_scaling_factor", 1.0)});
}
......
......@@ -39,7 +39,7 @@
#include "nav2_costmap_2d/layered_costmap.hpp"
#include "nav2_costmap_2d/observation_buffer.hpp"
#include "nav2_costmap_2d/testing_helper.hpp"
#include "nav2_util/node_utils.hpp"
class RclCppFixture
{
......@@ -54,7 +54,8 @@ class TestNode : public ::testing::Test
public:
TestNode()
{
node_ = rclcpp::Node::make_shared("obstacle_test_node");
node_ = rclcpp::Node::make_shared(
"obstacle_test_node", nav2_util::get_node_options_default());
}
~TestNode() {}
......
......@@ -40,6 +40,7 @@
#include "dwb_plugins/standard_traj_generator.hpp"
#include "dwb_plugins/limited_accel_generator.hpp"
#include "dwb_core/exceptions.hpp"
#include "nav2_util/node_utils.hpp"
using std::hypot;
using std::fabs;
......@@ -74,7 +75,7 @@ std::vector<rclcpp::Parameter> getDefaultKinematicParameters()
rclcpp::Node::SharedPtr makeTestNode(const std::string & name)
{
rclcpp::NodeOptions node_options;
rclcpp::NodeOptions node_options = nav2_util::get_node_options_default();
node_options.initial_parameters(getDefaultKinematicParameters());
return rclcpp::Node::make_shared(name, node_options);
}
......
......@@ -22,6 +22,7 @@
#include "nav2_dynamic_params/dynamic_params_client.hpp"
#include "rclcpp/rclcpp.hpp"
#include "nav2_util/lifecycle_utils.hpp"
#include "nav2_util/node_utils.hpp"
using namespace std::chrono_literals;
......@@ -63,7 +64,8 @@ class ClientTest : public ::testing::Test
public:
ClientTest()
{
node_ = rclcpp::Node::make_shared("dynamic_param_client_test");
node_ = rclcpp::Node::make_shared(
"dynamic_param_client_test", nav2_util::get_node_options_default());
dynamic_params_client_ = std::make_unique<DynamicParamsClientTest>(node_);
}
......
......@@ -18,6 +18,7 @@
#include <vector>
#include "nav2_dynamic_params/dynamic_params_client.hpp"
#include "nav2_util/node_utils.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
......@@ -25,9 +26,10 @@ int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node_A = rclcpp_lifecycle::LifecycleNode::make_shared("test_node");
auto node_A = rclcpp_lifecycle::LifecycleNode::make_shared(
"test_node", nav2_util::get_node_options_default());
auto node_B = rclcpp_lifecycle::LifecycleNode::make_shared(
"test_node", "test_namespace", rclcpp::NodeOptions());
"test_node", "test_namespace", nav2_util::get_node_options_default());
node_A->set_parameters({rclcpp::Parameter("foo", 1.0)});
node_B->set_parameters({rclcpp::Parameter("bar", 1)});
......
......@@ -18,6 +18,7 @@
#include "gtest/gtest.h"
#include "nav2_dynamic_params/dynamic_params_validator.hpp"
#include "nav2_util/node_utils.hpp"
#include "rclcpp/rclcpp.hpp"
using rcl_interfaces::msg::SetParametersResult;
......@@ -59,7 +60,8 @@ class ValidatorTest : public ::testing::Test
public:
ValidatorTest()
{
node_ = rclcpp::Node::make_shared("dynamic_param_validator_test");
node_ = rclcpp::Node::make_shared(
"dynamic_param_validator_test", nav2_util::get_node_options_default());
param_validator_ = std::make_unique<nav2_dynamic_params::DynamicParamsValidator>(node_);
}
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment