Skip to content

Commit e15affc

Browse files
committed
Test infrastructure
1 parent 8ae0a79 commit e15affc

2 files changed

Lines changed: 33 additions & 35 deletions

File tree

test/test_filter_utils.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -54,17 +54,16 @@ class TestFilter : public robot_body_filter::FilterBase<std::string>
5454

5555
TEST(FilterUtils, getParamVerboseFromDict)
5656
{
57-
ros::NodeHandle nh;
57+
rclcpp::Node nh("filter_utils");
5858

5959
auto filter = std::make_shared<TestFilter>();
6060
auto filterBase = std::dynamic_pointer_cast<filters::FilterBase<std::string>>(filter);
6161

62-
filterBase->configure("test_dict_config", nh);
62+
filterBase->configure("", "test_dict_config", nh.get_node_logging_interface(), nh.get_node_parameters_interface());
6363
}
6464

6565
int main(int argc, char **argv)
6666
{
6767
testing::InitGoogleTest(&argc, argv);
68-
ros::init(argc, argv, "test_filter_utils");
6968
return RUN_ALL_TESTS();
7069
}

test/test_robot_body_filter.cpp

Lines changed: 31 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -134,20 +134,20 @@ class RobotBodyFilterPointCloud2Test : public RobotBodyFilterPointCloud2
134134

135135
TEST(RobotBodyFilter, InitFromDict)
136136
{
137-
ros::NodeHandle nh;
137+
auto nh = std::make_shared<rclcpp::Node>("test_robot_body_filter");
138138

139139
auto filter = std::make_shared<RobotBodyFilterLaserScanTest>();
140140
auto filterBase = std::dynamic_pointer_cast<filters::FilterBase<sensor_msgs::msg::LaserScan>>(filter);
141141

142142
// test_robot_description parameter doesn't exist
143-
nh.deleteParam("test_robot_description");
144-
EXPECT_THROW(filterBase->configure("test_dict_config", nh), std::runtime_error);
143+
nh->set_parameter(rclcpp::Parameter("test_robot_description", ""));
144+
EXPECT_THROW(filterBase->configure("", "test_dict_config", nh->get_node_logging_interface(), nh->get_node_parameters_interface()), std::runtime_error);
145145
EXPECT_FALSE(filter->configured_);
146146
ASSERT_NE(nullptr, filter->tfFramesWatchdog);
147147

148148
// test that invalid robot model doesn't throw any exception, but also generates no filter shapes
149-
nh.setParam("test_robot_description", "<robot name='test'></robot>");
150-
filterBase->configure("test_dict_config", nh);
149+
nh->set_parameter(rclcpp::Parameter("test_robot_description", "<robot name='test'></robot>"));
150+
filterBase->configure("", "test_dict_config", nh->get_node_logging_interface(), nh->get_node_parameters_interface());
151151
EXPECT_EQ("test_robot_description", filter->robotDescriptionParam);
152152
EXPECT_EQ(0, filter->shapesToLinks.size());
153153
EXPECT_TRUE(filter->configured_);
@@ -158,14 +158,14 @@ TEST(RobotBodyFilter, InitFromDict)
158158

159159
TEST(RobotBodyFilter, LoadParams)
160160
{
161-
ros::NodeHandle nh;
161+
auto nh = std::make_shared<rclcpp::Node>("test_robot_body_filter");
162162

163163
auto filter = std::make_shared<RobotBodyFilterLaserScanTest>();
164164
auto filterBase = std::dynamic_pointer_cast<filters::FilterBase<sensor_msgs::msg::LaserScan>>(filter);
165165

166166
// test that invalid robot model doesn't throw any exception, but also generates no filter shapes
167-
nh.setParam("test_robot_description", "<robot name='test'></robot>");
168-
filterBase->configure("test_dict_config", nh);
167+
nh->set_parameter(rclcpp::Parameter("test_robot_description", "<robot name='test'></robot>"));
168+
filterBase->configure("", "test_dict_config", nh->get_node_logging_interface(), nh->get_node_parameters_interface());
169169

170170
EXPECT_EQ("odom", filter->fixedFrame);
171171
EXPECT_EQ("laser", filter->sensorFrame);
@@ -254,14 +254,14 @@ TEST(RobotBodyFilter, LoadParams)
254254

255255
TEST(RobotBodyFilter, LoadParamsAllConfig)
256256
{
257-
ros::NodeHandle nh;
257+
auto nh = std::make_shared<rclcpp::Node>("test_robot_body_filter");
258258

259259
auto filter = std::make_shared<RobotBodyFilterLaserScanTest>();
260260
auto filterBase = std::dynamic_pointer_cast<filters::FilterBase<sensor_msgs::msg::LaserScan>>(filter);
261261

262262
// test that invalid robot model doesn't throw any exception, but also generates no filter shapes
263-
nh.setParam("test_robot_description", "<robot name='test'></robot>");
264-
filterBase->configure("all_config", nh);
263+
nh->set_parameter(rclcpp::Parameter("test_robot_description", "<robot name='test'></robot>"));
264+
filterBase->configure("", "all_config", nh->get_node_logging_interface(), nh->get_node_parameters_interface());
265265

266266
EXPECT_EQ("odom", filter->fixedFrame);
267267
EXPECT_EQ("laser", filter->sensorFrame);
@@ -340,13 +340,13 @@ TEST(RobotBodyFilter, LoadParamsAllConfig)
340340

341341
TEST(RobotBodyFilter, ParseRobot)
342342
{
343-
ros::NodeHandle nh;
343+
auto nh = std::make_shared<rclcpp::Node>("test_robot_body_filter");
344344

345345
auto filter = std::make_shared<RobotBodyFilterLaserScanTest>();
346346
auto filterBase = std::dynamic_pointer_cast<filters::FilterBase<sensor_msgs::msg::LaserScan>>(filter);
347347

348-
nh.setParam("test_robot_description", ROBOT_URDF);
349-
filterBase->configure("test_dict_config", nh);
348+
nh->set_parameter(rclcpp::Parameter("test_robot_description", ROBOT_URDF));
349+
filterBase->configure("", "test_dict_config", nh->get_node_logging_interface(), nh->get_node_parameters_interface());
350350

351351
// base_link, base_link::big_collision_box::contains/shadow, laser::contains/shadow, antenna::contains/shadow
352352
EXPECT_EQ(7, filter->shapesToLinks.size());
@@ -401,8 +401,8 @@ TEST(RobotBodyFilter, ParseRobot)
401401

402402
// test reconfiguring (this happens when playing back a bag file and a new one starts playing)
403403
filter->clearRobotMask();
404-
nh.setParam("test_robot_description", ROBOT_URDF);
405-
filterBase->configure("test_dict_config", nh);
404+
nh->set_parameter(rclcpp::Parameter("test_robot_description", ROBOT_URDF));
405+
filterBase->configure("", "test_dict_config", nh->get_node_logging_interface(), nh->get_node_parameters_interface());
406406
EXPECT_EQ(7, filter->shapesToLinks.size());
407407
EXPECT_TRUE(filter->tfFramesWatchdog->isMonitored("laser"));
408408
EXPECT_TRUE(filter->tfFramesWatchdog->isMonitored("base_link"));
@@ -413,13 +413,13 @@ TEST(RobotBodyFilter, ParseRobot)
413413

414414
TEST(RobotBodyFilter, Transforms)
415415
{
416-
ros::NodeHandle nh;
416+
auto nh = std::make_shared<rclcpp::Node>("test_robot_body_filter");
417417

418418
auto filter = std::make_shared<RobotBodyFilterLaserScanTest>();
419419
auto filterBase = std::dynamic_pointer_cast<filters::FilterBase<sensor_msgs::msg::LaserScan>>(filter);
420420

421-
nh.setParam("test_robot_description", ROBOT_URDF);
422-
filterBase->configure("test_dict_config", nh);
421+
nh->set_parameter(rclcpp::Parameter("test_robot_description", ROBOT_URDF));
422+
filterBase->configure("", "test_dict_config", nh->get_node_logging_interface(), nh->get_node_parameters_interface());
423423

424424
geometry_msgs::msg::TransformStamped tf;
425425
tf.transform.rotation.w = 1.0;
@@ -504,13 +504,13 @@ TEST(RobotBodyFilter, Transforms)
504504

505505
TEST(RobotBodyFilter, ComputeMaskPointByPoint)
506506
{
507-
ros::NodeHandle nh;
507+
auto nh = std::make_shared<rclcpp::Node>("test_robot_body_filter");
508508

509509
auto filter = std::make_shared<RobotBodyFilterLaserScanTest>();
510510
auto filterBase = std::dynamic_pointer_cast<filters::FilterBase<sensor_msgs::msg::LaserScan>>(filter);
511511

512-
nh.setParam("test_robot_description", ROBOT_URDF);
513-
filterBase->configure("compute_mask_config_point_by_point", nh);
512+
nh->set_parameter(rclcpp::Parameter("test_robot_description", ROBOT_URDF));
513+
filterBase->configure("", "compute_mask_config_point_by_point", nh->get_node_logging_interface(), nh->get_node_parameters_interface());
514514

515515
Cloud cloud;
516516
cloud.header.frame_id = filter->filteringFrame;
@@ -1441,13 +1441,13 @@ TEST(RobotBodyFilter, ComputeMaskPointByPoint)
14411441

14421442
TEST(RobotBodyFilter, ComputeMaskAllAtOnce)
14431443
{
1444-
ros::NodeHandle nh;
1444+
auto nh = std::make_shared<rclcpp::Node>("test_robot_body_filter");
14451445

14461446
auto filter = std::make_shared<RobotBodyFilterPointCloud2Test>();
14471447
auto filterBase = std::dynamic_pointer_cast<filters::FilterBase<sensor_msgs::msg::PointCloud2>>(filter);
14481448

1449-
nh.setParam("test_robot_description", ROBOT_URDF);
1450-
filterBase->configure("compute_mask_config_all_at_once", nh);
1449+
nh->set_parameter(rclcpp::Parameter("test_robot_description", ROBOT_URDF));
1450+
filterBase->configure("", "compute_mask_config_all_at_once", nh->get_node_logging_interface(), nh->get_node_parameters_interface());
14511451

14521452
Cloud cloud;
14531453
cloud.header.frame_id = filter->filteringFrame;
@@ -2276,13 +2276,13 @@ TEST(RobotBodyFilter, ComputeMaskAllAtOnce)
22762276

22772277
TEST(RobotBodyFilter, UpdateLaserScan)
22782278
{
2279-
ros::NodeHandle nh;
2279+
auto nh = std::make_shared<rclcpp::Node>("test_robot_body_filter");
22802280

22812281
auto filter = std::make_shared<RobotBodyFilterLaserScanTest>();
22822282
auto filterBase = std::dynamic_pointer_cast<filters::FilterBase<sensor_msgs::msg::LaserScan>>(filter);
22832283

2284-
nh.setParam("test_robot_description", ROBOT_URDF);
2285-
filterBase->configure("compute_mask_config_point_by_point", nh);
2284+
nh->set_parameter(rclcpp::Parameter("test_robot_description", ROBOT_URDF));
2285+
filterBase->configure("", "compute_mask_config_point_by_point", nh->get_node_logging_interface(), nh->get_node_parameters_interface());
22862286

22872287
sensor_msgs::msg::LaserScan scan;
22882288
scan.header.frame_id = "laser";
@@ -2375,13 +2375,13 @@ TEST(RobotBodyFilter, UpdateLaserScan)
23752375

23762376
TEST(RobotBodyFilter, UpdatePointCloud2)
23772377
{
2378-
ros::NodeHandle nh;
2378+
auto nh = std::make_shared<rclcpp::Node>("test_robot_body_filter");
23792379

23802380
auto filter = std::make_shared<RobotBodyFilterPointCloud2Test>();
23812381
auto filterBase = std::dynamic_pointer_cast<filters::FilterBase<sensor_msgs::msg::PointCloud2>>(filter);
23822382

2383-
nh.setParam("test_robot_description", ROBOT_URDF);
2384-
filterBase->configure("compute_mask_config_all_at_once", nh);
2383+
nh->set_parameter(rclcpp::Parameter("test_robot_description", ROBOT_URDF));
2384+
filterBase->configure("", "compute_mask_config_all_at_once", nh->get_node_logging_interface(), nh->get_node_parameters_interface());
23852385

23862386
Cloud cloud;
23872387
cloud.header.frame_id = "laser";
@@ -2526,7 +2526,6 @@ TEST(RobotBodyFilter, UpdatePointCloud2)
25262526

25272527
int main(int argc, char **argv)
25282528
{
2529-
ros::init(argc, argv, "test_robot_body_filter");
25302529
testing::InitGoogleTest(&argc, argv);
25312530
return RUN_ALL_TESTS();
25322531
}

0 commit comments

Comments
 (0)