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: add published_time publisher debug to packages #6490

Merged
merged 4 commits into from
Mar 15, 2024
Merged
Show file tree
Hide file tree
Changes from all 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 @@ -37,7 +37,8 @@ class PublishedTimePublisher
{
}

void publish(const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
void publish_if_subscribed(
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
{
const auto & gid_key = publisher->get_gid();

Expand All @@ -57,7 +58,7 @@ class PublishedTimePublisher
}
}

void publish(
void publish_if_subscribed(
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const std_msgs::msg::Header & header)
{
const auto & gid_key = publisher->get_gid();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@

#include <Eigen/Core>
#include <Eigen/Geometry>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>

#include "autoware_auto_control_msgs/msg/ackermann_control_command.hpp"
#include "autoware_auto_control_msgs/msg/longitudinal_command.hpp"
Expand Down Expand Up @@ -121,6 +122,8 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node

std::unique_ptr<tier4_autoware_utils::LoggerLevelConfigure> logger_configure_;

std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;

void publishProcessingTime(
const double t_ms, const rclcpp::Publisher<Float64Stamped>::SharedPtr pub);
StopWatch<std::chrono::milliseconds> stop_watch_;
Expand Down
1 change: 1 addition & 0 deletions control/trajectory_follower_node/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
<depend>pure_pursuit</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tier4_autoware_utils</depend>
<depend>trajectory_follower_base</depend>
<depend>vehicle_info_util</depend>
<depend>visualization_msgs</depend>
Expand Down
5 changes: 4 additions & 1 deletion control/trajectory_follower_node/src/controller_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,8 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control
}

logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);

published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
}

Controller::LateralControllerMode Controller::getLateralControllerMode(
Expand Down Expand Up @@ -231,7 +233,8 @@ void Controller::callbackTimerControl()
out.longitudinal = lon_out.control_cmd;
control_cmd_pub_->publish(out);

// 6. publish debug marker
// 6. publish debug
published_time_publisher_->publish_if_subscribed(control_cmd_pub_, out.stamp);
publishDebugMarker(*input_data, lat_out);
}

Expand Down
1 change: 1 addition & 0 deletions control/vehicle_cmd_gate/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
<depend>rclcpp_components</depend>
<depend>std_srvs</depend>
<depend>tier4_api_utils</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_control_msgs</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_external_api_msgs</depend>
Expand Down
4 changes: 4 additions & 0 deletions control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -242,6 +242,8 @@
this, get_clock(), period_ns, std::bind(&VehicleCmdGate::publishStatus, this));

logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);

published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);

Check warning on line 246 in control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

VehicleCmdGate::VehicleCmdGate increases from 159 to 160 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
}

bool VehicleCmdGate::isHeartbeatTimeout(
Expand Down Expand Up @@ -456,6 +458,8 @@
// Publish commands
vehicle_cmd_emergency_pub_->publish(vehicle_cmd_emergency);
control_cmd_pub_->publish(filtered_commands.control);
published_time_publisher_->publish_if_subscribed(
control_cmd_pub_, filtered_commands.control.stamp);
adapi_pause_->publish();
moderate_stop_interface_->publish();

Expand Down
3 changes: 3 additions & 0 deletions control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <motion_utils/vehicle/vehicle_state_checker.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
#include <vehicle_cmd_gate/msg/is_filter_activated.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

Expand Down Expand Up @@ -248,6 +249,8 @@ class VehicleCmdGate : public rclcpp::Node
void publishMarkers(const IsFilterActivated & filter_activated);

std::unique_ptr<tier4_autoware_utils::LoggerLevelConfigure> logger_configure_;

std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
};

} // namespace vehicle_cmd_gate
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,13 @@
#define DETECTED_OBJECT_FEATURE_REMOVER__DETECTED_OBJECT_FEATURE_REMOVER_HPP_

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>

#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>

#include <memory>

namespace detected_object_feature_remover
{
using autoware_auto_perception_msgs::msg::DetectedObjects;
Expand All @@ -33,6 +36,7 @@ class DetectedObjectFeatureRemover : public rclcpp::Node
private:
rclcpp::Subscription<DetectedObjectsWithFeature>::SharedPtr sub_;
rclcpp::Publisher<DetectedObjects>::SharedPtr pub_;
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
void objectCallback(const DetectedObjectsWithFeature::ConstSharedPtr input);
void convert(const DetectedObjectsWithFeature & objs_with_feature, DetectedObjects & objs);
};
Expand Down
1 change: 1 addition & 0 deletions perception/detected_object_feature_remover/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
<depend>autoware_auto_perception_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_perception_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
pub_ = this->create_publisher<DetectedObjects>("~/output", rclcpp::QoS(1));
sub_ = this->create_subscription<DetectedObjectsWithFeature>(
"~/input", 1, std::bind(&DetectedObjectFeatureRemover::objectCallback, this, _1));
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);

Check warning on line 26 in perception/detected_object_feature_remover/src/detected_object_feature_remover.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detected_object_feature_remover/src/detected_object_feature_remover.cpp#L26

Added line #L26 was not covered by tests
}

void DetectedObjectFeatureRemover::objectCallback(
Expand All @@ -31,6 +32,7 @@
DetectedObjects output;
convert(*input, output);
pub_->publish(output);
published_time_publisher_->publish_if_subscribed(pub_, output.header.stamp);

Check warning on line 35 in perception/detected_object_feature_remover/src/detected_object_feature_remover.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detected_object_feature_remover/src/detected_object_feature_remover.cpp#L35

Added line #L35 was not covered by tests
}

void DetectedObjectFeatureRemover::convert(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
Expand Down Expand Up @@ -68,6 +69,8 @@ class ObjectLaneletFilterNode : public rclcpp::Node
bool isPolygonOverlapLanelets(const Polygon2d &, const lanelet::ConstLanelets &);
geometry_msgs::msg::Polygon setFootprint(
const autoware_auto_perception_msgs::msg::DetectedObject &);

std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
};

} // namespace object_lanelet_filter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,15 @@

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>

#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <memory>
#include <string>

namespace object_position_filter
Expand All @@ -51,6 +53,8 @@ class ObjectPositionFilterNode : public rclcpp::Node
float lower_bound_y_;
utils::FilterTargetLabel filter_target_;
bool isObjectInBounds(const autoware_auto_perception_msgs::msg::DetectedObject & object) const;

std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
};

} // namespace object_position_filter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>

#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
Expand Down Expand Up @@ -148,6 +149,7 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node
std::shared_ptr<Debugger> debugger_;
bool using_2d_validator_;
std::unique_ptr<Validator> validator_;
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;

private:
void onObjectsAndObstaclePointCloud(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/opencv.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>

#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
#include <nav_msgs/msg/occupancy_grid.hpp>
Expand All @@ -42,6 +43,7 @@ class OccupancyGridBasedValidator : public rclcpp::Node
message_filters::Subscriber<nav_msgs::msg::OccupancyGrid> occ_grid_sub_;
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;

typedef message_filters::sync_policies::ApproximateTime<
autoware_auto_perception_msgs::msg::DetectedObjects, nav_msgs::msg::OccupancyGrid>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@

debug_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "object_lanelet_filter");
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);

Check warning on line 58 in perception/detected_object_validation/src/object_lanelet_filter.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detected_object_validation/src/object_lanelet_filter.cpp#L58

Added line #L58 was not covered by tests
}

void ObjectLaneletFilterNode::mapCallback(
Expand Down Expand Up @@ -119,6 +120,7 @@
++index;
}
object_pub_->publish(output_object_msg);
published_time_publisher_->publish_if_subscribed(object_pub_, output_object_msg.header.stamp);

Check warning on line 123 in perception/detected_object_validation/src/object_lanelet_filter.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detected_object_validation/src/object_lanelet_filter.cpp#L123

Added line #L123 was not covered by tests

// Publish debug info
const double pipeline_latency =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
"input/object", rclcpp::QoS{1}, std::bind(&ObjectPositionFilterNode::objectCallback, this, _1));
object_pub_ = this->create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
"output/object", rclcpp::QoS{1});
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);

Check warning on line 45 in perception/detected_object_validation/src/object_position_filter.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detected_object_validation/src/object_position_filter.cpp#L45

Added line #L45 was not covered by tests
}

void ObjectPositionFilterNode::objectCallback(
Expand All @@ -65,6 +66,7 @@
}

object_pub_->publish(output_object_msg);
published_time_publisher_->publish_if_subscribed(object_pub_, output_object_msg.header.stamp);

Check warning on line 69 in perception/detected_object_validation/src/object_position_filter.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detected_object_validation/src/object_position_filter.cpp#L69

Added line #L69 was not covered by tests
}

bool ObjectPositionFilterNode::isObjectInBounds(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -309,6 +309,7 @@

const bool enable_debugger = declare_parameter<bool>("enable_debugger", false);
if (enable_debugger) debugger_ = std::make_shared<Debugger>(this);
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);

Check warning on line 312 in perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp#L312

Added line #L312 was not covered by tests
}
void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr & input_objects,
Expand Down Expand Up @@ -347,6 +348,7 @@
}

objects_pub_->publish(output);
published_time_publisher_->publish_if_subscribed(objects_pub_, output.header.stamp);

Check warning on line 351 in perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp#L351

Added line #L351 was not covered by tests
if (debugger_) {
debugger_->publishRemovedObjects(removed_objects);
debugger_->publishNeighborPointcloud(input_obstacle_pointcloud->header);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@

mean_threshold_ = declare_parameter<float>("mean_threshold", 0.6);
enable_debug_ = declare_parameter<bool>("enable_debug", false);
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);

Check warning on line 55 in perception/detected_object_validation/src/occupancy_grid_based_validator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detected_object_validation/src/occupancy_grid_based_validator.cpp#L55

Added line #L55 was not covered by tests
}

void OccupancyGridBasedValidator::onObjectsAndOccGrid(
Expand Down Expand Up @@ -85,6 +86,7 @@
}

objects_pub_->publish(output);
published_time_publisher_->publish_if_subscribed(objects_pub_, output.header.stamp);

Check warning on line 89 in perception/detected_object_validation/src/occupancy_grid_based_validator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detected_object_validation/src/occupancy_grid_based_validator.cpp#L89

Added line #L89 was not covered by tests

if (enable_debug_) showDebugImage(*input_occ_grid, transformed_objects, occ_grid);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp>
#include <rclcpp/rclcpp.hpp>
#include <shape_estimation/shape_estimator.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>

#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
Expand Down Expand Up @@ -83,6 +84,8 @@ class DetectionByTracker : public rclcpp::Node

detection_by_tracker::utils::TrackerIgnoreLabel tracker_ignore_;

std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;

void setMaxSearchRange();

void onObjects(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,7 @@
cluster_ = std::make_shared<euclidean_cluster::VoxelGridBasedEuclideanCluster>(
false, 10, 10000, 0.7, 0.3, 0);
debugger_ = std::make_shared<Debugger>(this);
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);

Check warning on line 180 in perception/detection_by_tracker/src/detection_by_tracker_core.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detection_by_tracker/src/detection_by_tracker_core.cpp#L180

Added line #L180 was not covered by tests
}

void DetectionByTracker::setMaxSearchRange()
Expand Down Expand Up @@ -221,6 +222,7 @@
!object_recognition_utils::transformObjects(
objects, input_msg->header.frame_id, tf_buffer_, transformed_objects)) {
objects_pub_->publish(detected_objects);
published_time_publisher_->publish_if_subscribed(objects_pub_, detected_objects.header.stamp);

Check warning on line 225 in perception/detection_by_tracker/src/detection_by_tracker_core.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detection_by_tracker/src/detection_by_tracker_core.cpp#L225

Added line #L225 was not covered by tests
return;
}
// to simplify post processes, convert tracked_objects to DetectedObjects message.
Expand Down Expand Up @@ -251,6 +253,7 @@
}

objects_pub_->publish(detected_objects);
published_time_publisher_->publish_if_subscribed(objects_pub_, detected_objects.header.stamp);

Check warning on line 256 in perception/detection_by_tracker/src/detection_by_tracker_core.cpp

View check run for this annotation

Codecov / codecov/patch

perception/detection_by_tracker/src/detection_by_tracker_core.cpp#L256

Added line #L256 was not covered by tests
debugger_->publishProcessingTime();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <lidar_centerpoint/detection_class_remapper.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>

#include <autoware_auto_perception_msgs/msg/detected_object_kinematics.hpp>
Expand Down Expand Up @@ -63,6 +64,8 @@ class LidarCenterPointNode : public rclcpp::Node
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_{
nullptr};
std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_ptr_{nullptr};

std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
};

} // namespace centerpoint
Expand Down
2 changes: 2 additions & 0 deletions perception/lidar_centerpoint/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,7 @@
RCLCPP_INFO(this->get_logger(), "TensorRT engine is built and shutdown node.");
rclcpp::shutdown();
}
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);

Check warning on line 129 in perception/lidar_centerpoint/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

LidarCenterPointNode::LidarCenterPointNode increases from 84 to 85 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 129 in perception/lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/src/node.cpp#L129

Added line #L129 was not covered by tests
}

void LidarCenterPointNode::pointCloudCallback(
Expand Down Expand Up @@ -163,6 +164,7 @@

if (objects_sub_count > 0) {
objects_pub_->publish(output_msg);
published_time_publisher_->publish_if_subscribed(objects_pub_, output_msg.header.stamp);

Check warning on line 167 in perception/lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/src/node.cpp#L167

Added line #L167 was not covered by tests
}

// add processing time for debug
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
#include <tier4_autoware_utils/ros/transform_listener.hpp>
#include <tier4_autoware_utils/ros/uuid_helper.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>
Expand Down Expand Up @@ -199,6 +200,8 @@ class MapBasedPredictionNode : public rclcpp::Node
std::vector<double> distance_set_for_no_intention_to_walk_;
std::vector<double> timeout_set_for_no_intention_to_walk_;

std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;

// Member Functions
void mapCallback(const HADMapBin::ConstSharedPtr msg);
void trafficSignalsCallback(const TrafficSignalArray::ConstSharedPtr msg);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1769 to 1771, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.
//
// 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 @@ -811,6 +811,7 @@
processing_time_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "map_based_prediction");

published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);

Check warning on line 814 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

MapBasedPredictionNode::MapBasedPredictionNode increases from 88 to 89 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 814 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L814

Added line #L814 was not covered by tests
set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&MapBasedPredictionNode::onParam, this, std::placeholders::_1));

Expand Down Expand Up @@ -1112,6 +1113,7 @@

// Publish Results
pub_objects_->publish(output);
published_time_publisher_->publish_if_subscribed(pub_objects_, output.header.stamp);

Check warning on line 1116 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

MapBasedPredictionNode::objectsCallback already has high cyclomatic complexity, and now it increases in Lines of Code from 177 to 178. 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 1116 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L1116

Added line #L1116 was not covered by tests
pub_debug_markers_->publish(debug_markers);
const auto processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
const auto cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
Expand Down
Loading
Loading