Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

perf(occupancy_grid_map_outlier_filter): improve performance #5980

Merged
merged 10 commits into from
Mar 14, 2024
Original file line number Diff line number Diff line change
Expand Up @@ -239,19 +239,42 @@
void OccupancyGridMapOutlierFilterComponent::splitPointCloudFrontBack(
const PointCloud2::ConstSharedPtr & input_pc, PointCloud2 & front_pc, PointCloud2 & behind_pc)
{
PclPointCloud tmp_behind_pc;
PclPointCloud tmp_front_pc;
for (sensor_msgs::PointCloud2ConstIterator<float> x(*input_pc, "x"), y(*input_pc, "y"),
z(*input_pc, "z");
x != x.end(); ++x, ++y, ++z) {
size_t front_count = 0;
size_t behind_count = 0;

for (sensor_msgs::PointCloud2ConstIterator<float> x(*input_pc, "x"); x != x.end(); ++x) {

Check warning on line 245 in perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp#L245

Added line #L245 was not covered by tests
if (*x < 0.0) {
tmp_behind_pc.push_back(pcl::PointXYZ(*x, *y, *z));
behind_count++;

Check warning on line 247 in perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp#L247

Added line #L247 was not covered by tests
} else {
tmp_front_pc.push_back(pcl::PointXYZ(*x, *y, *z));
front_count++;

Check warning on line 249 in perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp#L249

Added line #L249 was not covered by tests
}
}
pcl::toROSMsg(tmp_front_pc, front_pc);
pcl::toROSMsg(tmp_behind_pc, behind_pc);

sensor_msgs::PointCloud2Modifier front_pc_modifier(front_pc);
sensor_msgs::PointCloud2Modifier behind_pc_modifier(behind_pc);
front_pc_modifier.setPointCloud2FieldsByString(1, "xyz");
behind_pc_modifier.setPointCloud2FieldsByString(1, "xyz");
front_pc_modifier.resize(front_count);
behind_pc_modifier.resize(behind_count);

Check warning on line 258 in perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp#L255-L258

Added lines #L255 - L258 were not covered by tests

sensor_msgs::PointCloud2Iterator<float> fr_iter(front_pc, "x");
sensor_msgs::PointCloud2Iterator<float> be_iter(behind_pc, "x");

Check warning on line 261 in perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp#L260-L261

Added lines #L260 - L261 were not covered by tests

for (sensor_msgs::PointCloud2ConstIterator<float> in_iter(*input_pc, "x");
in_iter != in_iter.end(); ++in_iter) {
if (*in_iter < 0.0) {
*be_iter = in_iter[0];
be_iter[1] = in_iter[1];
be_iter[2] = in_iter[2];

Check warning on line 268 in perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp#L263-L268

Added lines #L263 - L268 were not covered by tests
++be_iter;
} else {
*fr_iter = in_iter[0];
fr_iter[1] = in_iter[1];
fr_iter[2] = in_iter[2];

Check warning on line 273 in perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp#L271-L273

Added lines #L271 - L273 were not covered by tests
++fr_iter;
}
}

Check warning on line 277 in perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

OccupancyGridMapOutlierFilterComponent::splitPointCloudFrontBack has 2 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
front_pc.header = input_pc->header;
behind_pc.header = input_pc->header;
}
Expand Down
Loading