Skip to content

Commit 1671854

Browse files
committed
Update some tests
Signed-off-by: Alberto Tudela <[email protected]>
1 parent 22ee3dd commit 1671854

File tree

2 files changed

+37
-9
lines changed

2 files changed

+37
-9
lines changed

test/test_integration.cpp

+19-4
Original file line numberDiff line numberDiff line change
@@ -33,19 +33,34 @@ TEST(LaserSegmentationTest, integration) {
3333

3434
// Create and configure the laser_segmentation node
3535
auto seg_node = std::make_shared<laserSegmentation>();
36+
// Set some parameters
37+
nav2_util::declare_parameter_if_not_declared(
38+
seg_node, "min_points_segment", rclcpp::ParameterValue(1));
39+
nav2_util::declare_parameter_if_not_declared(
40+
seg_node, "max_points_segment", rclcpp::ParameterValue(3));
3641
seg_node->configure();
3742
seg_node->activate();
3843

3944
// Create a scan message with three points
4045
sensor_msgs::msg::LaserScan scan;
4146
scan.header.frame_id = "laser_frame";
47+
scan.angle_min = -M_PI / 2;
48+
scan.angle_max = M_PI / 2;
49+
scan.angle_increment = M_PI / 180;
50+
scan.time_increment = 0.1;
51+
scan.scan_time = 0.1;
52+
scan.range_min = 0.0;
53+
scan.range_max = 10.0;
54+
scan.ranges.push_back(1.0);
55+
scan.ranges.push_back(1.1);
56+
scan.ranges.push_back(2.0);
57+
scan.ranges.push_back(2.1);
58+
scan.ranges.push_back(3.0);
59+
scan.ranges.push_back(3.2);
60+
scan.ranges.push_back(12.0);
4261
// Publish the message
4362
scan_pub->publish(scan);
4463

45-
// Spin the laser_segmentation node
46-
// Shouldn get any susbcriptions count
47-
rclcpp::spin_some(seg_node->get_node_base_interface());
48-
4964
// Create the segments subscriber node
5065
auto sub_node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("segment_subscriber");
5166
sub_node->configure();

test/test_laser_segmentation.cpp

+18-5
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,11 @@ class laserSegmentationFixture : public laserSegmentation
2222
laserSegmentationFixture()
2323
: laserSegmentation() {}
2424

25+
void scan_callback(const sensor_msgs::msg::LaserScan::SharedPtr msg)
26+
{
27+
laserSegmentation::scan_callback(msg);
28+
}
29+
2530
std::vector<slg::Segment2D> filter_segments(const std::vector<slg::Segment2D> & segments)
2631
{
2732
return laserSegmentation::filter_segments(segments);
@@ -52,6 +57,9 @@ TEST(LaserSegmentationTest, configure) {
5257
node, "segmentation_type", rclcpp::ParameterValue("jump_distance"));
5358
node->configure();
5459
node->activate();
60+
// Call an empty callback
61+
auto msg = std::make_shared<sensor_msgs::msg::LaserScan>();
62+
node->scan_callback(msg);
5563
node->deactivate();
5664
node->cleanup();
5765

@@ -203,9 +211,9 @@ TEST(LaserSegmentationTest, filterSegments) {
203211

204212
// Set the parameters
205213
nav2_util::declare_parameter_if_not_declared(
206-
node, "min_points_segment", rclcpp::ParameterValue(1));
214+
node, "min_points_segment", rclcpp::ParameterValue(2));
207215
nav2_util::declare_parameter_if_not_declared(
208-
node, "max_points_segment", rclcpp::ParameterValue(2));
216+
node, "max_points_segment", rclcpp::ParameterValue(4));
209217
nav2_util::declare_parameter_if_not_declared(
210218
node, "min_avg_distance_from_sensor", rclcpp::ParameterValue(0.1));
211219
nav2_util::declare_parameter_if_not_declared(
@@ -220,19 +228,24 @@ TEST(LaserSegmentationTest, filterSegments) {
220228
node, "noise_reduction", rclcpp::ParameterValue(0.1));
221229
node->configure();
222230

223-
// Set a segment list with 0 segments
231+
// Set a segment list with 1 segments
224232
std::vector<slg::Segment2D> segment_list;
233+
slg::Segment2D segment;
234+
segment.add_point(slg::Point2D(0.0, 0.0, slg::BACKGROUND));
235+
segment_list.push_back(segment);
236+
// Filter the segments
225237
auto filtered_segments = node->filter_segments(segment_list);
226238
// Check the filtered segments
227239
EXPECT_EQ(filtered_segments.size(), 0);
228240

229-
// Set a segment list with 3 segments of 1 point
241+
// Set a segment list with 4 segments of 1 point
230242
segment_list.clear();
231-
slg::Segment2D segment;
243+
segment.clear();
232244
segment.add_point(slg::Point2D(0.0, 0.0, slg::BACKGROUND));
233245
segment_list.push_back(segment);
234246
segment_list.push_back(segment);
235247
segment_list.push_back(segment);
248+
segment_list.push_back(segment);
236249
// Filter the segments
237250
filtered_segments = node->filter_segments(segment_list);
238251
// Check the filtered segments

0 commit comments

Comments
 (0)