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

fix: add delay time for reschedule gpu task #14

Draft
wants to merge 1 commit into
base: fix/add_run_length_compressed
Choose a base branch
from
Draft
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 @@ -27,6 +27,7 @@
color_map_path: "$(var data_path)/tensorrt_yolox/semseg_color_map.csv"
score_threshold: 0.35
nms_threshold: 0.7
inference_delay_ms: 0 # Duration time for yolox inference delay in milliseconds.

precision: "int8" # Operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8].
calibration_algorithm: "Entropy" # Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: [Entropy, (Legacy | Percentile), MinMax].
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
color_map_path: "$(var data_path)/tensorrt_yolox/semseg_color_map.csv"
score_threshold: 0.35 # Objects with a score lower than this value will be ignored. This threshold will be ignored if specified model contains EfficientNMS_TRT module in it.
nms_threshold: 0.7 # Detection results will be ignored if IoU over this value. This threshold will be ignored if specified model contains EfficientNMS_TRT module in it.
inference_delay_ms: 0 # Duration time for yolox inference delay in milliseconds.

precision: "fp16" # Operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8].
calibration_algorithm: "MinMax" # Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: [Entropy, (Legacy | Percentile), MinMax].
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,7 @@ class TrtYoloXNode : public rclcpp::Node
RoiOverlaySemsegLabel roi_overlay_segment_labels_;
std::unique_ptr<autoware::universe_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_;
int inference_delay_ms_ = 0;
};

} // namespace autoware::tensorrt_yolox
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,10 @@
#include <autoware_perception_msgs/msg/object_classification.hpp>

#include <algorithm>
#include <chrono>
#include <memory>
#include <string>
#include <thread>
#include <utility>
#include <vector>

Expand Down Expand Up @@ -80,6 +82,8 @@ TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options)
roi_overlay_segment_labels_.PEDESTRIAN =
declare_parameter<bool>("roi_overlay_segment_label.PEDESTRIAN");
roi_overlay_segment_labels_.ANIMAL = declare_parameter<bool>("roi_overlay_segment_label.ANIMAL");
inference_delay_ms_ = declare_parameter("inference_delay_ms");

replaceLabelMap();

tensorrt_common::BuildConfig build_config(
Expand Down Expand Up @@ -146,7 +150,7 @@ void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg)
std::vector<cv::Mat> masks = {cv::Mat(cv::Size(height, width), CV_8UC1, cv::Scalar(0))};
std::vector<cv::Mat> color_masks = {
cv::Mat(cv::Size(height, width), CV_8UC3, cv::Scalar(0, 0, 0))};

std::this_thread::sleep_for(std::chrono::milliseconds(inference_delay_ms_));
if (!trt_yolox_->doInference({in_image_ptr->image}, objects, masks, color_masks)) {
RCLCPP_WARN(this->get_logger(), "Fail to inference");
return;
Expand Down
Loading