Skip to content

Commit

Permalink
Merge branch 'lidar-apollo-instance-segmentation' of https://github.c…
Browse files Browse the repository at this point in the history
…om/Interplai/autoware.universe into perception-trafiic-light-classifier
  • Loading branch information
karishma1911 committed Dec 19, 2023
2 parents 60b4030 + b2f5cfb commit 73ddb90
Show file tree
Hide file tree
Showing 2 changed files with 89 additions and 10 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for lidar_apollo_instance_segmentation",
"type": "object",
"definitions": {
"lidar_apollo_instance_segmentation": {
"type": "object",
"properties": {
"score_threshold": {
"type": "number",
"default": 0.8,
"description": "If the score of a detected object is lower than this value, the object is ignored."
},
"range": {
"type": "number",
"default": 60,
"description": "Half of the length of feature map sides. [m]."
},
"width": {
"type": "number",
"default": 640,
"description": "The grid width of feature map."
},
"height": {
"type": "number",
"default": 640,
"description": "The grid height of feature map."
},
"precision": {
"type": "string",
"default": "fp32"
},
"use_intensity_feature": {
"type": "boolean",
"default": "true",
"description": "The flag to use intensity feature of pointcloud."
},
"use_constant_feature": {
"type": "boolean",
"default": "false",
"description": "The flag to use direction and distance feature of pointcloud."
},
"target_frame": {
"type": "string",
"default": "base_link",
"description": "Pointcloud data is transformed into this frame."
},
"z_offset": {
"type": "number",
"default": -2.0,
"description": "z offset from target frame. [m]."
}
},
"required": [
"score_threshold",
"range",
"width",
"height",
"precision",
"use_intensity_feature",
"use_constant_feature",
"target_frame",
"z_offset"
]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/lidar_apollo_instance_segmentation"
}
},
"required": ["ros__parameters"]
}
},
"required": ["/**"]
}
20 changes: 10 additions & 10 deletions perception/lidar_apollo_instance_segmentation/src/detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,16 +28,16 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node *
int range, width, height;
bool use_intensity_feature, use_constant_feature;
std::string onnx_file;
score_threshold_ = node_->declare_parameter("score_threshold", 0.8);
range = node_->declare_parameter("range", 60);
width = node_->declare_parameter("width", 640);
height = node_->declare_parameter("height", 640);
onnx_file = node_->declare_parameter("onnx_file", "vls-128.onnx");
use_intensity_feature = node_->declare_parameter("use_intensity_feature", true);
use_constant_feature = node_->declare_parameter("use_constant_feature", true);
target_frame_ = node_->declare_parameter("target_frame", "base_link");
z_offset_ = node_->declare_parameter<float>("z_offset", -2.0);
const auto precision = node_->declare_parameter("precision", "fp32");
score_threshold_ = node_->declare_parameter<double>("score_threshold");
range = node_->declare_parameter<int>("range");
width = node_->declare_parameter<int>("width");
height = node_->declare_parameter<int>("height");
onnx_file = node_->declare_parameter<std::string>("onnx_file");
use_intensity_feature = node_->declare_parameter<bool>("use_intensity_feature");
use_constant_feature = node_->declare_parameter<bool>("use_constant_feature");
target_frame_ = node_->declare_parameter<std::string>("target_frame");
z_offset_ = node_->declare_parameter<float>("z_offset");
const auto precision = node_->declare_parameter<std::string>("precision");

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

0 comments on commit 73ddb90

Please sign in to comment.