Skip to content

Commit 22ee3dd

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

File tree

4 files changed

+147
-44
lines changed

4 files changed

+147
-44
lines changed

include/laser_segmentation/laser_segmentation.hpp

+8
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,14 @@ class laserSegmentation : public rclcpp_lifecycle::LifecycleNode
105105
*/
106106
void scan_callback(const sensor_msgs::msg::LaserScan::SharedPtr scan);
107107

108+
/**
109+
* @brief Filter the segments using the parameters
110+
*
111+
* @param segments List of segments
112+
* @return std::vector<slg::Segment2D> Filtered segments
113+
*/
114+
std::vector<slg::Segment2D> filter_segments(const std::vector<slg::Segment2D> & segments);
115+
108116
/**
109117
* @brief Create the segment array message
110118
*

src/laser_segmentation.cpp

+33-25
Original file line numberDiff line numberDiff line change
@@ -132,12 +132,40 @@ void laserSegmentation::scan_callback(const sensor_msgs::msg::LaserScan::SharedP
132132
segmentation_->perform_segmentation(point_list, segment_list);
133133

134134
// Filter segments
135+
auto segment_filtered_list = filter_segments(segment_list);
136+
137+
// Identification of segments and set angular distance
138+
for (std::vector<slg::Segment2D>::size_type s = 0; s < segment_filtered_list.size(); s++) {
139+
double angle = std::min(
140+
scan_msg->angle_max - segment_filtered_list[s].max_angle(),
141+
segment_filtered_list[s].min_angle() - scan_msg->angle_min);
142+
segment_filtered_list[s].set_id(s);
143+
segment_filtered_list[s].set_angular_distance_to_closest_boundary(angle);
144+
}
145+
146+
// Publish the segment array
147+
slg_msgs::msg::SegmentArray segment_array_msg;
148+
segment_array_msg.header = scan_msg->header;
149+
for (const auto & segment : segment_filtered_list) {
150+
segment_array_msg.segments.push_back(segment);
151+
}
152+
segment_pub_->publish(segment_array_msg);
153+
154+
// Publish visualization markers
155+
segment_viz_points_pub_->publish(
156+
create_segment_viz_points(scan_msg->header, segment_filtered_list));
157+
}
158+
159+
std::vector<slg::Segment2D> laserSegmentation::filter_segments(
160+
const std::vector<slg::Segment2D> & segments)
161+
{
162+
std::vector<slg::Segment2D> filtered_segments;
163+
filtered_segments.reserve(segments.size());
164+
135165
double squared_min_segment_width = params_->min_segment_width * params_->min_segment_width;
136166
double squared_max_segment_width = params_->max_segment_width * params_->max_segment_width;
137-
std::vector<slg::Segment2D> segment_filtered_list;
138-
segment_filtered_list.reserve(segment_list.size());
139167

140-
for (const auto & segment : segment_list) {
168+
for (const auto & segment : segments) {
141169
// By number of points
142170
if (segment.size() < params_->min_points_segment ||
143171
segment.size() > params_->max_points_segment)
@@ -159,29 +187,9 @@ void laserSegmentation::scan_callback(const sensor_msgs::msg::LaserScan::SharedP
159187
continue;
160188
}
161189

162-
segment_filtered_list.push_back(segment);
163-
}
164-
165-
// Identification of segments and set angular distance
166-
for (std::vector<slg::Segment2D>::size_type s = 0; s < segment_filtered_list.size(); s++) {
167-
double angle = std::min(
168-
scan_msg->angle_max - segment_filtered_list[s].max_angle(),
169-
segment_filtered_list[s].min_angle() - scan_msg->angle_min);
170-
segment_filtered_list[s].set_id(s);
171-
segment_filtered_list[s].set_angular_distance_to_closest_boundary(angle);
190+
filtered_segments.push_back(segment);
172191
}
173-
174-
// Publish the segment array
175-
slg_msgs::msg::SegmentArray segment_array_msg;
176-
segment_array_msg.header = scan_msg->header;
177-
for (const auto & segment : segment_filtered_list) {
178-
segment_array_msg.segments.push_back(segment);
179-
}
180-
segment_pub_->publish(segment_array_msg);
181-
182-
// Publish visualization markers
183-
segment_viz_points_pub_->publish(
184-
create_segment_viz_points(scan_msg->header, segment_filtered_list));
192+
return filtered_segments;
185193
}
186194

187195
visualization_msgs::msg::MarkerArray laserSegmentation::create_segment_viz_points(

test/test_integration.cpp

+4-19
Original file line numberDiff line numberDiff line change
@@ -33,34 +33,19 @@ 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));
4136
seg_node->configure();
4237
seg_node->activate();
4338

4439
// Create a scan message with three points
4540
sensor_msgs::msg::LaserScan scan;
4641
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);
6142
// Publish the message
6243
scan_pub->publish(scan);
6344

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

test/test_laser_segmentation.cpp

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

25+
std::vector<slg::Segment2D> filter_segments(const std::vector<slg::Segment2D> & segments)
26+
{
27+
return laserSegmentation::filter_segments(segments);
28+
}
29+
2530
visualization_msgs::msg::MarkerArray create_segment_viz_points(
2631
std_msgs::msg::Header header, std::vector<slg::Segment2D> segment_list)
2732
{
@@ -192,6 +197,103 @@ TEST(LaserSegmentationTest, createVizPoints) {
192197
EXPECT_EQ(marker_array.markers[3].text, "0");
193198
}
194199

200+
TEST(LaserSegmentationTest, filterSegments) {
201+
// Create the node
202+
auto node = std::make_shared<laserSegmentationFixture>();
203+
204+
// Set the parameters
205+
nav2_util::declare_parameter_if_not_declared(
206+
node, "min_points_segment", rclcpp::ParameterValue(1));
207+
nav2_util::declare_parameter_if_not_declared(
208+
node, "max_points_segment", rclcpp::ParameterValue(2));
209+
nav2_util::declare_parameter_if_not_declared(
210+
node, "min_avg_distance_from_sensor", rclcpp::ParameterValue(0.1));
211+
nav2_util::declare_parameter_if_not_declared(
212+
node, "max_avg_distance_from_sensor", rclcpp::ParameterValue(10.0));
213+
nav2_util::declare_parameter_if_not_declared(
214+
node, "min_segment_width", rclcpp::ParameterValue(0.1));
215+
nav2_util::declare_parameter_if_not_declared(
216+
node, "max_segment_width", rclcpp::ParameterValue(10.0));
217+
nav2_util::declare_parameter_if_not_declared(
218+
node, "distance_threshold", rclcpp::ParameterValue(0.1));
219+
nav2_util::declare_parameter_if_not_declared(
220+
node, "noise_reduction", rclcpp::ParameterValue(0.1));
221+
node->configure();
222+
223+
// Set a segment list with 0 segments
224+
std::vector<slg::Segment2D> segment_list;
225+
auto filtered_segments = node->filter_segments(segment_list);
226+
// Check the filtered segments
227+
EXPECT_EQ(filtered_segments.size(), 0);
228+
229+
// Set a segment list with 3 segments of 1 point
230+
segment_list.clear();
231+
slg::Segment2D segment;
232+
segment.add_point(slg::Point2D(0.0, 0.0, slg::BACKGROUND));
233+
segment_list.push_back(segment);
234+
segment_list.push_back(segment);
235+
segment_list.push_back(segment);
236+
// Filter the segments
237+
filtered_segments = node->filter_segments(segment_list);
238+
// Check the filtered segments
239+
EXPECT_EQ(filtered_segments.size(), 0);
240+
241+
// Set a segment list with 1 segment with centroid below the minimum distance
242+
segment_list.clear();
243+
segment.clear();
244+
segment.add_point(slg::Point2D(0.0, 0.0, slg::BACKGROUND));
245+
segment_list.push_back(segment);
246+
// Filter the segments
247+
filtered_segments = node->filter_segments(segment_list);
248+
// Check the filtered segments
249+
EXPECT_EQ(filtered_segments.size(), 0);
250+
251+
// Set a segment list with 1 segment with centroid above the maximum distance
252+
segment_list.clear();
253+
segment.clear();
254+
segment.add_point(slg::Point2D(11.0, 11.0, slg::BACKGROUND));
255+
segment_list.push_back(segment);
256+
// Filter the segments
257+
filtered_segments = node->filter_segments(segment_list);
258+
// Check the filtered segments
259+
EXPECT_EQ(filtered_segments.size(), 0);
260+
261+
// Set a segment list with 1 segment with width below the minimum width
262+
segment_list.clear();
263+
segment.clear();
264+
segment.add_point(slg::Point2D(0.0, 0.0, slg::BACKGROUND));
265+
segment.add_point(slg::Point2D(0.0, 0.0, slg::BACKGROUND));
266+
segment_list.push_back(segment);
267+
// Filter the segments
268+
filtered_segments = node->filter_segments(segment_list);
269+
// Check the filtered segments
270+
EXPECT_EQ(filtered_segments.size(), 0);
271+
272+
// Set a segment list with 1 segment with width above the maximum width
273+
segment_list.clear();
274+
segment.clear();
275+
segment.add_point(slg::Point2D(0.0, 0.0, slg::BACKGROUND));
276+
segment.add_point(slg::Point2D(10.0, 10.0, slg::BACKGROUND));
277+
segment_list.push_back(segment);
278+
// Filter the segments
279+
filtered_segments = node->filter_segments(segment_list);
280+
// Check the filtered segments
281+
EXPECT_EQ(filtered_segments.size(), 0);
282+
283+
// Set a segment list with 1 segment with 2 points
284+
segment_list.clear();
285+
segment.clear();
286+
segment.add_point(slg::Point2D(0.0, 0.0, slg::BACKGROUND));
287+
segment.add_point(slg::Point2D(1.0, 1.0, slg::BACKGROUND));
288+
segment_list.push_back(segment);
289+
// Filter the segments
290+
filtered_segments = node->filter_segments(segment_list);
291+
// Check the filtered segments
292+
EXPECT_EQ(filtered_segments.size(), 1);
293+
EXPECT_EQ(filtered_segments[0].centroid().x, 0.5);
294+
EXPECT_EQ(filtered_segments[0].centroid().y, 0.5);
295+
}
296+
195297
int main(int argc, char ** argv)
196298
{
197299
testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)