Skip to content

Commit ae8b599

Browse files
committed
Increase code coverage
Signed-off-by: mini-1235 <[email protected]>
1 parent 487f1ed commit ae8b599

File tree

2 files changed

+36
-5
lines changed

2 files changed

+36
-5
lines changed

nav2_controller/plugins/test/path_handler.cpp

Lines changed: 35 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,6 @@ TEST(PathHandlerTests, GetAndPrunePath)
8484
auto node = std::make_shared<nav2::LifecycleNode>("my_node");
8585
auto costmap_ros = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
8686
"dummy_costmap", "", true);
87-
std::string name = "test";
8887
rclcpp_lifecycle::State state;
8988
costmap_ros->on_configure(state);
9089

@@ -109,7 +108,6 @@ TEST(PathHandlerTests, TestBounds)
109108
auto results = costmap_ros->set_parameters_atomically(
110109
{rclcpp::Parameter("global_frame", "odom"),
111110
rclcpp::Parameter("robot_base_frame", "base_link")});
112-
std::string name = "test";
113111
rclcpp_lifecycle::State state;
114112
costmap_ros->on_configure(state);
115113

@@ -157,7 +155,6 @@ TEST(PathHandlerTests, TestTransforms)
157155
node->declare_parameter("dummy.max_robot_pose_search_dist", rclcpp::ParameterValue(99999.9));
158156
auto costmap_ros = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
159157
"dummy_costmap", "", true);
160-
std::string name = "test";
161158
rclcpp_lifecycle::State state;
162159
costmap_ros->on_configure(state);
163160

@@ -213,7 +210,6 @@ TEST(PathHandlerTests, TestInversionToleranceChecks)
213210
auto node = std::make_shared<nav2::LifecycleNode>("my_node");
214211
auto costmap_ros = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
215212
"dummy_costmap", "", true);
216-
std::string name = "test";
217213
rclcpp_lifecycle::State state;
218214
costmap_ros->on_configure(state);
219215

@@ -250,6 +246,41 @@ TEST(PathHandlerTests, TestInversionToleranceChecks)
250246
EXPECT_TRUE(handler.isWithinInversionTolerancesWrapper(robot_pose));
251247
}
252248

249+
TEST(PathHandlerTests, TestDynamicParams)
250+
{
251+
PathHandlerWrapper handler;
252+
auto node = std::make_shared<nav2::LifecycleNode>("my_node");
253+
auto costmap_ros = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
254+
"dummy_costmap", "", true);
255+
rclcpp_lifecycle::State state;
256+
costmap_ros->on_configure(state);
257+
258+
handler.initialize(node, node->get_logger(), "dummy", costmap_ros, costmap_ros->getTfBuffer());
259+
260+
auto rec_param = std::make_shared<rclcpp::AsyncParametersClient>(
261+
node->get_node_base_interface(), node->get_node_topics_interface(),
262+
node->get_node_graph_interface(),
263+
node->get_node_services_interface());
264+
265+
auto results = rec_param->set_parameters_atomically({
266+
rclcpp::Parameter("dummy.max_robot_pose_search_dist", 100.0),
267+
rclcpp::Parameter("dummy.inversion_xy_tolerance", 200.0),
268+
rclcpp::Parameter("dummy.inversion_yaw_tolerance", 300.0),
269+
rclcpp::Parameter("dummy.prune_distance", 400.0),
270+
rclcpp::Parameter("dummy.enforce_path_inversion", true),
271+
});
272+
273+
rclcpp::spin_until_future_complete(
274+
node->get_node_base_interface(),
275+
results);
276+
277+
EXPECT_EQ(node->get_parameter("dummy.max_robot_pose_search_dist").as_double(), 100.0);
278+
EXPECT_EQ(node->get_parameter("dummy.inversion_xy_tolerance").as_double(), 200.0);
279+
EXPECT_EQ(node->get_parameter("dummy.inversion_yaw_tolerance").as_double(), 300.0);
280+
EXPECT_EQ(node->get_parameter("dummy.prune_distance").as_double(), 400.0);
281+
EXPECT_EQ(node->get_parameter("dummy.enforce_path_inversion").as_bool(), true);
282+
}
283+
253284
int main(int argc, char **argv)
254285
{
255286
::testing::InitGoogleTest(&argc, argv);

nav2_controller/src/controller_server.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,12 +74,12 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
7474
try {
7575
param_handler_ = std::make_unique<ParameterHandler>(
7676
node, get_logger());
77-
params_ = param_handler_->getParams();
7877
} catch (const std::exception & ex) {
7978
RCLCPP_FATAL(get_logger(), "%s", ex.what());
8079
on_cleanup(state);
8180
return nav2::CallbackReturn::FAILURE;
8281
}
82+
params_ = param_handler_->getParams();
8383

8484
for (size_t i = 0; i != params_->progress_checker_ids.size(); i++) {
8585
try {

0 commit comments

Comments
 (0)