Skip to content

Commit

Permalink
Merge remote main
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin committed Sep 10, 2024
1 parent fcbfc60 commit 9e8dad4
Show file tree
Hide file tree
Showing 28 changed files with 403 additions and 96 deletions.
1 change: 0 additions & 1 deletion map/map_loader/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
<maintainer email="[email protected]">NGUYEN Viet Anh</maintainer>
<maintainer email="[email protected]">Taiki Yamada</maintainer>
<maintainer email="[email protected]">Shintaro Sakoda</maintainer>
<maintainer email="[email protected]">Mamoru Sobue</maintainer>

<license>Apache License 2.0</license>
<author email="[email protected]">Ryohsuke Mitsudome</author>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,3 +19,6 @@
radial_divider_angle_deg: 1.0
use_recheck_ground_cluster: true
use_lowest_point: true

# debug parameters
publish_processing_time_detail: false
Original file line number Diff line number Diff line change
Expand Up @@ -12,3 +12,6 @@
voxel_size_z: 0.04
height_threshold: 0.01
debug: false

# debug parameters
publish_processing_time_detail: false
Original file line number Diff line number Diff line change
Expand Up @@ -12,3 +12,6 @@
min_height_threshold: 0.15
concentric_divider_distance: 0.0
reclass_distance_threshold: 0.1

# debug parameters
publish_processing_time_detail: false
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,6 @@
radial_divider_angle_deg: 1.0
use_recheck_ground_cluster: true
use_lowest_point: true

# debug parameters
publish_processing_time_detail: false
1 change: 1 addition & 0 deletions perception/autoware_ground_segmentation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

<depend>ament_index_cpp</depend>
<depend>autoware_pointcloud_preprocessor</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>libopencv-dev</depend>
<depend>pcl_conversions</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@ PlaneBasis getPlaneBasis(const Eigen::Vector3d & plane_normal)
}

using autoware::pointcloud_preprocessor::get_param;
using autoware::universe_utils::ScopedTimeTrack;

RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptions & options)
: Filter("RANSACGroundFilter", options)
Expand Down Expand Up @@ -118,6 +119,15 @@ RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptio

managed_tf_buffer_ =
std::make_unique<autoware::universe_utils::ManagedTransformBuffer>(this, has_static_tf_only_);

bool use_time_keeper = declare_parameter<bool>("publish_processing_time_detail");
if (use_time_keeper) {
detailed_processing_time_publisher_ =
this->create_publisher<autoware::universe_utils::ProcessingTimeDetail>(
"~/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);
}
}

void RANSACGroundFilterComponent::setDebugPublisher()
Expand Down Expand Up @@ -204,6 +214,9 @@ void RANSACGroundFilterComponent::applyRANSAC(
const pcl::PointCloud<PointType>::Ptr & input, pcl::PointIndices::Ptr & output_inliers,
pcl::ModelCoefficients::Ptr & output_coefficients)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

pcl::SACSegmentation<PointType> seg;
seg.setOptimizeCoefficients(true);
seg.setRadiusLimits(0.3, std::numeric_limits<double>::max());
Expand All @@ -219,6 +232,9 @@ void RANSACGroundFilterComponent::filter(
const PointCloud2::ConstSharedPtr & input, [[maybe_unused]] const IndicesPtr & indices,
PointCloud2 & output)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

Check warning on line 237 in perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

RANSACGroundFilterComponent::filter has a cyclomatic complexity of 9, 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.
std::scoped_lock lock(mutex_);
sensor_msgs::msg::PointCloud2::SharedPtr input_transformed_ptr(new sensor_msgs::msg::PointCloud2);
if (!transformPointCloud(base_frame_, input, input_transformed_ptr)) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define RANSAC_GROUND_FILTER__NODE_HPP_

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

#include <autoware/universe_utils/ros/managed_transform_buffer.hpp>

Expand Down Expand Up @@ -85,6 +86,11 @@ class RANSACGroundFilterComponent : public autoware::pointcloud_preprocessor::Fi
Eigen::Vector3d unit_vec_ = Eigen::Vector3d::UnitZ();
std::unique_ptr<autoware::universe_utils::ManagedTransformBuffer> managed_tf_buffer_{nullptr};

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

/*!
* Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame
* @param[in] in_target_frame Coordinate system to perform transform
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,14 @@

#include "node.hpp"

#include <memory>
#include <string>
#include <vector>

namespace autoware::ground_segmentation
{
using autoware::pointcloud_preprocessor::get_param;
using autoware::universe_utils::ScopedTimeTrack;

RayGroundFilterComponent::RayGroundFilterComponent(const rclcpp::NodeOptions & options)
: Filter("RayGroundFilter", options)
Expand Down Expand Up @@ -69,13 +71,25 @@ RayGroundFilterComponent::RayGroundFilterComponent(const rclcpp::NodeOptions & o
using std::placeholders::_1;
set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&RayGroundFilterComponent::paramCallback, this, _1));

bool use_time_keeper = declare_parameter<bool>("publish_processing_time_detail");
if (use_time_keeper) {
detailed_processing_time_publisher_ =
this->create_publisher<autoware::universe_utils::ProcessingTimeDetail>(
"~/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);
}
}

void RayGroundFilterComponent::ConvertXYZIToRTZColor(
const pcl::PointCloud<PointType_>::Ptr in_cloud, PointCloudXYZRTColor & out_organized_points,
std::vector<pcl::PointIndices> & out_radial_divided_indices,
std::vector<PointCloudXYZRTColor> & out_radial_ordered_clouds)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

out_organized_points.resize(in_cloud->points.size());
out_radial_divided_indices.clear();
out_radial_divided_indices.resize(radial_dividers_num_);
Expand Down Expand Up @@ -153,6 +167,9 @@ void RayGroundFilterComponent::ClassifyPointCloud(
std::vector<PointCloudXYZRTColor> & in_radial_ordered_clouds,
pcl::PointIndices & out_ground_indices, pcl::PointIndices & out_no_ground_indices)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

Check warning on line 172 in perception/autoware_ground_segmentation/src/ray_ground_filter/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

RayGroundFilterComponent::ClassifyPointCloud increases in cyclomatic complexity from 18 to 19, 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.
out_ground_indices.indices.clear();
out_no_ground_indices.indices.clear();
#pragma omp for
Expand Down Expand Up @@ -275,6 +292,9 @@ void RayGroundFilterComponent::ExtractPointsIndices(
const PointCloud2::ConstSharedPtr in_cloud_ptr, const pcl::PointIndices & in_indices,
PointCloud2::SharedPtr ground_cloud_msg_ptr, PointCloud2::SharedPtr no_ground_cloud_msg_ptr)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

initializePointCloud2(in_cloud_ptr, ground_cloud_msg_ptr);
initializePointCloud2(in_cloud_ptr, no_ground_cloud_msg_ptr);
int point_step = in_cloud_ptr->point_step;
Expand Down Expand Up @@ -312,6 +332,9 @@ void RayGroundFilterComponent::filter(
const PointCloud2::ConstSharedPtr & input, [[maybe_unused]] const IndicesPtr & indices,
PointCloud2 & output)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);

std::scoped_lock lock(mutex_);

pcl::PointCloud<PointType_>::Ptr current_sensor_cloud_ptr(new pcl::PointCloud<PointType_>);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@
#ifndef RAY_GROUND_FILTER__NODE_HPP_
#define RAY_GROUND_FILTER__NODE_HPP_

#include "autoware/universe_utils/system/time_keeper.hpp"

#include <sensor_msgs/msg/point_cloud2.hpp>

#include <pcl/filters/extract_indices.h>
Expand Down Expand Up @@ -72,6 +74,7 @@
#include <tf2_ros/transform_listener.h>

#include <chrono>
#include <memory>
#include <string>
#include <vector>

Expand Down Expand Up @@ -140,6 +143,11 @@ class RayGroundFilterComponent : public autoware::pointcloud_preprocessor::Filte
pcl::PointCloud<PointType_>::Ptr previous_cloud_ptr_; // holds the previous groundless result of
// ground classification

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

/*!
* Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame
* @param[in] in_target_frame Coordinate system to perform transform
Expand Down
Loading

0 comments on commit 9e8dad4

Please sign in to comment.