Skip to content

Commit aabe5bc

Browse files
Remove redundant set_parameter calls.
Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com>
1 parent c306953 commit aabe5bc

File tree

3 files changed

+0
-12
lines changed

3 files changed

+0
-12
lines changed

nav2_costmap_2d/test/unit/costmap_filter_service_test.cpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -70,8 +70,6 @@ class TestNode : public ::testing::Test
7070
// Set CostmapFilter ROS-parameters
7171
node_->declare_parameter(
7272
std::string(FILTER_NAME) + ".filter_info_topic", rclcpp::ParameterValue("filter_info"));
73-
node_->set_parameter(
74-
rclcpp::Parameter(std::string(FILTER_NAME) + ".filter_info_topic", "filter_info"));
7573
}
7674

7775
~TestNode()

nav2_costmap_2d/test/unit/keepout_filter_test.cpp

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -219,12 +219,8 @@ void TestNode::createKeepoutFilter(const std::string & global_frame)
219219

220220
node_->declare_parameter(
221221
std::string(FILTER_NAME) + ".transform_tolerance", rclcpp::ParameterValue(0.5));
222-
node_->set_parameter(
223-
rclcpp::Parameter(std::string(FILTER_NAME) + ".transform_tolerance", 0.5));
224222
node_->declare_parameter(
225223
std::string(FILTER_NAME) + ".filter_info_topic", rclcpp::ParameterValue(INFO_TOPIC));
226-
node_->set_parameter(
227-
rclcpp::Parameter(std::string(FILTER_NAME) + ".filter_info_topic", INFO_TOPIC));
228224

229225
keepout_filter_ = std::make_shared<nav2_costmap_2d::KeepoutFilter>();
230226
keepout_filter_->initialize(&layers, std::string(FILTER_NAME), tf_buffer_.get(), node_, nullptr);

nav2_costmap_2d/test/unit/speed_filter_test.cpp

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -352,16 +352,10 @@ bool TestNode::createSpeedFilter(const std::string & global_frame)
352352

353353
node_->declare_parameter(
354354
std::string(FILTER_NAME) + ".transform_tolerance", rclcpp::ParameterValue(0.5));
355-
node_->set_parameter(
356-
rclcpp::Parameter(std::string(FILTER_NAME) + ".transform_tolerance", 0.5));
357355
node_->declare_parameter(
358356
std::string(FILTER_NAME) + ".filter_info_topic", rclcpp::ParameterValue(INFO_TOPIC));
359-
node_->set_parameter(
360-
rclcpp::Parameter(std::string(FILTER_NAME) + ".filter_info_topic", INFO_TOPIC));
361357
node_->declare_parameter(
362358
std::string(FILTER_NAME) + ".speed_limit_topic", rclcpp::ParameterValue(SPEED_LIMIT_TOPIC));
363-
node_->set_parameter(
364-
rclcpp::Parameter(std::string(FILTER_NAME) + ".speed_limit_topic", SPEED_LIMIT_TOPIC));
365359

366360
speed_filter_ = std::make_shared<nav2_costmap_2d::SpeedFilter>();
367361
speed_filter_->initialize(&layers, FILTER_NAME, tf_buffer_.get(), node_, nullptr);

0 commit comments

Comments
 (0)