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

feat(occupancy_grid_map_outlier_filter): add time_keeper #8597

Merged
Show file tree
Hide file tree
Changes from 8 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -10,3 +10,6 @@
cost_threshold: 45
use_radius_search_2d_filter: true
enable_debugger: false

# debug parameters
publish_processing_time_detail: False
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc. All rights reserved.

Check notice on line 1 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Large Method

OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2 is no longer above the threshold for lines of code
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -39,6 +39,8 @@

namespace
{
using autoware::universe_utils::ScopedTimeTrack;

bool transformPointcloud(
const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2,
const std::string & target_frame, sensor_msgs::msg::PointCloud2 & output)
Expand Down Expand Up @@ -263,11 +265,24 @@
if (enable_debugger) {
debugger_ptr_ = std::make_shared<Debugger>(*this);
}

// time keeper
bool use_time_keeper = declare_parameter<bool>("publish_processing_time_detail");

Check warning on line 270 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L270

Added line #L270 was not covered by tests
technolojin marked this conversation as resolved.
Show resolved Hide resolved
if (use_time_keeper) {
detailed_processing_time_publisher_ =
this->create_publisher<autoware::universe_utils::ProcessingTimeDetail>(

Check warning on line 273 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L273

Added line #L273 was not covered by tests
"~/debug/processing_time_detail_ms", 1);
auto time_keeper = autoware::universe_utils::TimeKeeper(detailed_processing_time_publisher_);
time_keeper_ = std::make_shared<autoware::universe_utils::TimeKeeper>(time_keeper);

Check warning on line 276 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L275-L276

Added lines #L275 - L276 were not covered by tests
}
}

void OccupancyGridMapOutlierFilterComponent::splitPointCloudFrontBack(
const PointCloud2::ConstSharedPtr & input_pc, PointCloud2 & front_pc, PointCloud2 & behind_pc)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;

Check warning on line 283 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L283

Added line #L283 was not covered by tests
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

int x_offset = input_pc->fields[pcl::getFieldIndex(*input_pc, "x")].offset;
int point_step = input_pc->point_step;
size_t front_count = 0;
Expand Down Expand Up @@ -295,6 +310,9 @@
void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2(
const OccupancyGrid::ConstSharedPtr & input_ogm, const PointCloud2::ConstSharedPtr & input_pc)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;

Check warning on line 313 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L313

Added line #L313 was not covered by tests
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

stop_watch_ptr_->toc("processing_time", true);
// Transform to occupancy grid map frame

Expand All @@ -309,12 +327,19 @@

PointCloud2 ogm_frame_pc{};
PointCloud2 ogm_frame_input_behind_pc{};
if (
!transformPointcloud(input_front_pc, *tf2_, input_ogm->header.frame_id, ogm_frame_pc) ||
!transformPointcloud(
input_behind_pc, *tf2_, input_ogm->header.frame_id, ogm_frame_input_behind_pc)) {
return;
{ // scope for the timekeeper to track the time spent on transformPointcloud
technolojin marked this conversation as resolved.
Show resolved Hide resolved
std::unique_ptr<ScopedTimeTrack> inner_st_ptr;

Check warning on line 331 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L331

Added line #L331 was not covered by tests
if (time_keeper_)
inner_st_ptr = std::make_unique<ScopedTimeTrack>("transformPointcloud", *time_keeper_);

Check warning on line 333 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L333

Added line #L333 was not covered by tests

if (
!transformPointcloud(input_front_pc, *tf2_, input_ogm->header.frame_id, ogm_frame_pc) ||
!transformPointcloud(
input_behind_pc, *tf2_, input_ogm->header.frame_id, ogm_frame_input_behind_pc)) {

Check warning on line 338 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L336-L338

Added lines #L336 - L338 were not covered by tests
return;
}
}

// Occupancy grid map based filter
PointCloud2 high_confidence_pc{};
PointCloud2 low_confidence_pc{};
Expand All @@ -330,34 +355,55 @@
PointCloud2 outlier_pc{};
initializerPointCloud2(low_confidence_pc, outlier_pc);
initializerPointCloud2(low_confidence_pc, filtered_low_confidence_pc);
initializerPointCloud2(low_confidence_pc, outlier_pc);

if (radius_search_2d_filter_ptr_) {
std::unique_ptr<ScopedTimeTrack> inner_st_ptr;

Check warning on line 360 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L360

Added line #L360 was not covered by tests
if (time_keeper_)
inner_st_ptr = std::make_unique<ScopedTimeTrack>("radius_search_2d_filter", *time_keeper_);

Check warning on line 362 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L362

Added line #L362 was not covered by tests

auto pc_frame_pose_stamped = getPoseStamped(
*tf2_, input_ogm->header.frame_id, input_pc->header.frame_id, input_ogm->header.stamp);
radius_search_2d_filter_ptr_->filter(
high_confidence_pc, low_confidence_pc, pc_frame_pose_stamped.pose, filtered_low_confidence_pc,
outlier_pc);
} else {
std::unique_ptr<ScopedTimeTrack> inner_st_ptr;

Check warning on line 370 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L370

Added line #L370 was not covered by tests
if (time_keeper_)
inner_st_ptr = std::make_unique<ScopedTimeTrack>("low_confidence_pc_filter", *time_keeper_);

Check warning on line 372 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L372

Added line #L372 was not covered by tests

std::memcpy(&outlier_pc.data[0], &low_confidence_pc.data[0], low_confidence_pc.data.size());
outlier_pc.data.resize(low_confidence_pc.data.size());
}

// Concatenate high confidence pointcloud from occupancy grid map and non-outlier pointcloud
PointCloud2 ogm_frame_filtered_pc{};
concatPointCloud2(ogm_frame_filtered_pc, high_confidence_pc);
concatPointCloud2(ogm_frame_filtered_pc, filtered_low_confidence_pc);
concatPointCloud2(ogm_frame_filtered_pc, out_ogm_pc);
concatPointCloud2(ogm_frame_filtered_pc, ogm_frame_input_behind_pc);
finalizePointCloud2(ogm_frame_pc, ogm_frame_filtered_pc);
{
auto base_link_frame_filtered_pc_ptr = std::make_unique<PointCloud2>();

auto base_link_frame_filtered_pc_ptr = std::make_unique<PointCloud2>();

Check warning on line 386 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L386

Added line #L386 was not covered by tests
{ // scope for the timekeeper to track the time spent on transformPointcloud
std::unique_ptr<ScopedTimeTrack> inner_st_ptr;

Check warning on line 388 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L388

Added line #L388 was not covered by tests
if (time_keeper_)
inner_st_ptr = std::make_unique<ScopedTimeTrack>("transformPointcloud", *time_keeper_);

Check warning on line 390 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L390

Added line #L390 was not covered by tests

ogm_frame_filtered_pc.header = ogm_frame_pc.header;
if (!transformPointcloud(
ogm_frame_filtered_pc, *tf2_, base_link_frame_, *base_link_frame_filtered_pc_ptr)) {
return;
}
}

{ // scope for the timekeeper to track the time spent on publishing pointcloud
std::unique_ptr<ScopedTimeTrack> inner_st_ptr;

Check warning on line 400 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L400

Added line #L400 was not covered by tests
if (time_keeper_)
inner_st_ptr = std::make_unique<ScopedTimeTrack>("publish_pointcloud", *time_keeper_);

Check warning on line 402 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L402

Added line #L402 was not covered by tests

pointcloud_pub_->publish(std::move(base_link_frame_filtered_pc_ptr));
}

Check warning on line 406 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2 has a cyclomatic complexity of 13, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check warning on line 406 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2 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.
if (debugger_ptr_) {
finalizePointCloud2(ogm_frame_pc, high_confidence_pc);
finalizePointCloud2(ogm_frame_pc, filtered_low_confidence_pc);
Expand All @@ -381,13 +427,19 @@
void OccupancyGridMapOutlierFilterComponent::initializerPointCloud2(
const PointCloud2 & input, PointCloud2 & output)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;

Check warning on line 430 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L430

Added line #L430 was not covered by tests
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

output.point_step = input.point_step;
output.data.resize(input.data.size());
}

void OccupancyGridMapOutlierFilterComponent::finalizePointCloud2(
const PointCloud2 & input, PointCloud2 & output)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;

Check warning on line 440 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L440

Added line #L440 was not covered by tests
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

output.header = input.header;
output.point_step = input.point_step;
output.fields = input.fields;
Expand All @@ -401,6 +453,9 @@
void OccupancyGridMapOutlierFilterComponent::concatPointCloud2(
PointCloud2 & output, const PointCloud2 & input)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;

Check warning on line 456 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L456

Added line #L456 was not covered by tests
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

size_t output_size = output.data.size();
output.data.resize(output.data.size() + input.data.size());
std::memcpy(&output.data[output_size], &input.data[0], input.data.size());
Expand All @@ -409,6 +464,9 @@
const OccupancyGrid & occupancy_grid_map, const PointCloud2 & pointcloud,
PointCloud2 & high_confidence, PointCloud2 & low_confidence, PointCloud2 & out_ogm)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;

Check warning on line 467 in perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp#L467

Added line #L467 was not covered by tests
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

int x_offset = pointcloud.fields[pcl::getFieldIndex(pointcloud, "x")].offset;
int y_offset = pointcloud.fields[pcl::getFieldIndex(pointcloud, "y")].offset;
size_t high_confidence_size = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include "autoware/pointcloud_preprocessor/filter.hpp"
#include "autoware/universe_utils/ros/published_time_publisher.hpp"
#include "autoware/universe_utils/system/time_keeper.hpp"

#include <pcl/common/impl/common.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -128,6 +129,11 @@ class OccupancyGridMapOutlierFilterComponent : public rclcpp::Node
std::string map_frame_;
std::string base_link_frame_;
int cost_threshold_;

// time keeper
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr
detailed_processing_time_publisher_;
std::shared_ptr<autoware::universe_utils::TimeKeeper> time_keeper_;
};
} // namespace autoware::occupancy_grid_map_outlier_filter

Expand Down
Loading