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(tensorrt_yolo): multi gpu on component container #2297

Merged
merged 4 commits into from
Nov 29, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
2 changes: 2 additions & 0 deletions perception/tensorrt_yolo/include/tensorrt_yolo/nodelet.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,8 @@ class TensorrtYoloNodelet : public rclcpp::Node

yolo::Config yolo_config_;

int gpu_device_id_;

std::vector<std::string> labels_;
std::unique_ptr<float[]> out_scores_;
std::unique_ptr<float[]> out_boxes_;
Expand Down
8 changes: 6 additions & 2 deletions perception/tensorrt_yolo/src/nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options)
std::string calib_image_directory = declare_parameter("calib_image_directory", "");
std::string calib_cache_file = declare_parameter("calib_cache_file", "");
std::string mode = declare_parameter("mode", "FP32");
int gpu_device_id = declare_parameter("gpu_id", 0);
gpu_device_id_ = declare_parameter("gpu_id", 0);
kaancolak marked this conversation as resolved.
Show resolved Hide resolved
yolo_config_.num_anchors = declare_parameter("num_anchors", 3);
auto anchors = declare_parameter(
"anchors", std::vector<double>{
Expand All @@ -67,7 +67,7 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options)
yolo_config_.use_darknet_layer = declare_parameter("use_darknet_layer", true);
yolo_config_.ignore_thresh = declare_parameter("ignore_thresh", 0.5);

if (!yolo::set_cuda_device(gpu_device_id)) {
if (!yolo::set_cuda_device(gpu_device_id_)) {
RCLCPP_ERROR(this->get_logger(), "Given GPU not exist or suitable");
}

Expand Down Expand Up @@ -134,6 +134,10 @@ void TensorrtYoloNodelet::callback(const sensor_msgs::msg::Image::ConstSharedPtr

tier4_perception_msgs::msg::DetectedObjectsWithFeature out_objects;

if (!yolo::set_cuda_device(gpu_device_id_)) {
RCLCPP_ERROR(this->get_logger(), "Given GPU not exist or suitable");
kaancolak marked this conversation as resolved.
Show resolved Hide resolved
}

cv_bridge::CvImagePtr in_image_ptr;
try {
in_image_ptr = cv_bridge::toCvCopy(in_image_msg, sensor_msgs::image_encodings::BGR8);
Expand Down