@@ -50,9 +50,9 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options)
50
50
std::string label_file = declare_parameter (" label_file" , " " );
51
51
std::string calib_image_directory = declare_parameter (" calib_image_directory" , " " );
52
52
std::string calib_cache_file = declare_parameter (" calib_cache_file" , " " );
53
- std::string mode = declare_parameter (" mode" , " FP32 " );
54
- gpu_device_id_ = declare_parameter (" gpu_id" , 0 );
55
- yolo_config_.num_anchors = declare_parameter (" num_anchors" , 3 );
53
+ std::string mode = declare_parameter<std::string> (" mode" );
54
+ gpu_device_id_ = declare_parameter< int > (" gpu_id" );
55
+ yolo_config_.num_anchors = declare_parameter< int > (" num_anchors" );
56
56
auto anchors = declare_parameter (
57
57
" anchors" , std::vector<double >{
58
58
10 , 13 , 16 , 30 , 33 , 23 , 30 , 61 , 62 , 45 , 59 , 119 , 116 , 90 , 156 , 198 , 373 , 326 });
@@ -61,11 +61,11 @@ TensorrtYoloNodelet::TensorrtYoloNodelet(const rclcpp::NodeOptions & options)
61
61
auto scale_x_y = declare_parameter (" scale_x_y" , std::vector<double >{1.0 , 1.0 , 1.0 });
62
62
std::vector<float > scale_x_y_float (scale_x_y.begin (), scale_x_y.end ());
63
63
yolo_config_.scale_x_y = scale_x_y_float;
64
- yolo_config_.score_thresh = declare_parameter (" score_thresh" , 0.1 );
65
- yolo_config_.iou_thresh = declare_parameter (" iou_thresh" , 0.45 );
66
- yolo_config_.detections_per_im = declare_parameter (" detections_per_im" , 100 );
67
- yolo_config_.use_darknet_layer = declare_parameter (" use_darknet_layer" , true );
68
- yolo_config_.ignore_thresh = declare_parameter (" ignore_thresh" , 0.5 );
64
+ yolo_config_.score_thresh = declare_parameter< double > (" score_thresh" );
65
+ yolo_config_.iou_thresh = declare_parameter< double > (" iou_thresh" );
66
+ yolo_config_.detections_per_im = declare_parameter< int > (" detections_per_im" );
67
+ yolo_config_.use_darknet_layer = declare_parameter< bool > (" use_darknet_layer" );
68
+ yolo_config_.ignore_thresh = declare_parameter< double > (" ignore_thresh" );
69
69
70
70
if (!yolo::set_cuda_device (gpu_device_id_)) {
71
71
RCLCPP_ERROR (this ->get_logger (), " Given GPU not exist or suitable" );
0 commit comments