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

chore(tensorrt_yolox): add processing time and cyclic time debug topic #7126

Merged
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
@@ -19,6 +19,8 @@
#include <opencv2/opencv.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tensorrt_yolox/tensorrt_yolox.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>

#include <sensor_msgs/msg/image.hpp>
#include <std_msgs/msg/header.hpp>
@@ -61,6 +63,8 @@ class TrtYoloXNode : public rclcpp::Node

LabelMap label_map_;
std::unique_ptr<tensorrt_yolox::TrtYoloX> trt_yolox_;
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_;
};

} // namespace tensorrt_yolox
25 changes: 25 additions & 0 deletions perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp
Original file line number Diff line number Diff line change
@@ -29,6 +29,14 @@
TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options)
: Node("tensorrt_yolox", node_options)
{
{
stop_watch_ptr_ =
std::make_unique<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>>();
debug_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "tensorrt_yolox");
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");
}

Check warning on line 39 in perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

TrtYoloXNode::TrtYoloXNode increases from 80 to 88 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.
Comment on lines +32 to +39
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@badai-nguyen
Sorry for the delay in my review. Let me confirm one point: Do you intend to enable this debug_publisher_ at all times? In my opinion, I would like to put a condition to enable/disable this kind of debug feature on actual deployment.

using std::placeholders::_1;
using std::chrono_literals::operator""ms;

@@ -132,6 +140,7 @@

void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg)
{
stop_watch_ptr_->toc("processing_time", true);
tier4_perception_msgs::msg::DetectedObjectsWithFeature out_objects;

cv_bridge::CvImagePtr in_image_ptr;
@@ -173,6 +182,22 @@

out_objects.header = msg->header;
objects_pub_->publish(out_objects);

if (debug_publisher_) {
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds(
(this->get_clock()->now() - out_objects.header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
}
}

bool TrtYoloXNode::readLabelFile(const std::string & label_path)

Unchanged files with check annotations Beta

constexpr double min_dist = 0.001;
if (tier4_autoware_utils::calcDistance2d(p, point) < min_dist) {
return i;

Check warning on line 308 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

GitHub Actions / spell-check-partial

Unknown word (optionallly)
}
}
inout_path->points, in_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold);
// vector.insert(i) inserts element on the left side of v[i]
// the velocity need to be zero order hold(from prior point)
int insert_idx = closest_idx;

Check warning on line 329 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

GitHub Actions / spell-check-partial

Unknown word (optionallly)
autoware_auto_planning_msgs::msg::PathPointWithLaneId inserted_point =
inout_path->points.at(closest_idx);
if (planning_utils::isAheadOf(in_pose, inout_path->points.at(closest_idx).point.pose)) {
*/
bool checkObstacleInBlindSpot(
lanelet::LaneletMapConstPtr lanelet_map_ptr,
lanelet::routing::RoutingGraphPtr routing_graph_ptr,

Check warning on line 146 in planning/behavior_velocity_blind_spot_module/src/scene.hpp

GitHub Actions / spell-check-partial

Unknown word (Dafe)
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr,
const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose);