Skip to content

Commit 583022d

Browse files
committed
perception/lidar_apollo_instance_segmentation
1 parent 8e209a1 commit 583022d

File tree

2 files changed

+88
-9
lines changed

2 files changed

+88
-9
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for lidar_apollo_instance_segmentation",
4+
"type": "object",
5+
"definitions": {
6+
"velodyne_monitor": {
7+
"type": "object",
8+
"properties": {
9+
"score_threshold": {
10+
"type": "number",
11+
"default": 0.8,
12+
"description": "If the score of a detected object is lower than this value, the object is ignored."
13+
},
14+
"range": {
15+
"type": "number",
16+
"default": 60,
17+
"description": "Half of the length of feature map sides. [m]."
18+
},
19+
"width": {
20+
"type": "number",
21+
"default": 640,
22+
"description": "The grid width of feature map."
23+
},
24+
"height": {
25+
"type": "number",
26+
"default": 640,
27+
"description": "The grid height of feature map."
28+
},
29+
"precision": {
30+
"type": "string",
31+
"default": "fp32"
32+
},
33+
"use_intensity_feature": {
34+
"type": "boolean",
35+
"default": "true",
36+
"description": "The flag to use intensity feature of pointcloud."
37+
},
38+
"use_constant_feature": {
39+
"type": "boolean",
40+
"default": "false",
41+
"description": "The flag to use direction and distance feature of pointcloud."
42+
},
43+
"target_frame": {
44+
"type": "string",
45+
"default": "base_link",
46+
"description": "Pointcloud data is transformed into this frame."
47+
},
48+
"z_offset": {
49+
"type": "number",
50+
"default": -2.0,
51+
"description": " z offset from target frame. [m]."
52+
}
53+
},
54+
"required": [
55+
"score_threshold",
56+
"range",
57+
"width",
58+
"height",
59+
"precision",
60+
"use_intensity_feature",
61+
"use_constant_feature",
62+
"target_frame",
63+
"z_offset"
64+
]
65+
}
66+
},
67+
"properties": {
68+
"/**": {
69+
"type": "object",
70+
"properties": {
71+
"ros__parameters": {
72+
"$ref": "#/definitions/lidar_apollo_instance_segmentation"
73+
}
74+
},
75+
"required": ["ros__parameters"]
76+
}
77+
},
78+
"required": ["/**"]
79+
}

perception/lidar_apollo_instance_segmentation/src/detector.cpp

+9-9
Original file line numberDiff line numberDiff line change
@@ -28,16 +28,16 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node *
2828
int range, width, height;
2929
bool use_intensity_feature, use_constant_feature;
3030
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");
3939
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");
4141

4242
trt_common_ = std::make_unique<tensorrt_common::TrtCommon>(
4343
onnx_file, precision, nullptr, tensorrt_common::BatchConfig{1, 1, 1}, 1 << 30);

0 commit comments

Comments
 (0)