@@ -28,16 +28,16 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node *
28
28
int range, width, height;
29
29
bool use_intensity_feature, use_constant_feature;
30
30
std::string onnx_file;
31
- score_threshold_ = node_->declare_parameter (" score_threshold" , 0.8 );
32
- range = node_->declare_parameter (" range" , 60 );
33
- width = node_->declare_parameter (" width" , 640 );
34
- height = node_->declare_parameter (" height" , 640 );
35
- onnx_file = node_->declare_parameter (" onnx_file" , " vls-128.onnx " );
36
- use_intensity_feature = node_->declare_parameter (" use_intensity_feature" , true );
37
- use_constant_feature = node_->declare_parameter (" use_constant_feature" , true );
38
- target_frame_ = node_->declare_parameter (" target_frame" , " base_link " );
31
+ score_threshold_ = node_->declare_parameter < double > (" score_threshold" );
32
+ range = node_->declare_parameter < int > (" range" );
33
+ width = node_->declare_parameter < int > (" width" );
34
+ height = node_->declare_parameter < int > (" height" );
35
+ onnx_file = node_->declare_parameter <std::string> (" onnx_file" );
36
+ use_intensity_feature = node_->declare_parameter < bool > (" use_intensity_feature" );
37
+ use_constant_feature = node_->declare_parameter < bool > (" use_constant_feature" );
38
+ target_frame_ = node_->declare_parameter <std::string> (" target_frame" );
39
39
z_offset_ = node_->declare_parameter <float >(" z_offset" , -2.0 );
40
- const auto precision = node_->declare_parameter (" precision" , " fp32" );
40
+ const auto precision = node_->declare_parameter <std::string> (" precision" , " fp32" );
41
41
42
42
trt_common_ = std::make_unique<tensorrt_common::TrtCommon>(
43
43
onnx_file, precision, nullptr , tensorrt_common::BatchConfig{1 , 1 , 1 }, 1 << 30 );
0 commit comments