From 583022daf1102d6f640f209b586b900c3aba60a2 Mon Sep 17 00:00:00 2001 From: karishma Date: Fri, 1 Dec 2023 11:24:35 +0530 Subject: [PATCH] perception/lidar_apollo_instance_segmentation --- .../lidar_apollo_instance_segmentation.json | 79 +++++++++++++++++++ .../src/detector.cpp | 18 ++--- 2 files changed, 88 insertions(+), 9 deletions(-) create mode 100644 perception/lidar_apollo_instance_segmentation/schema/lidar_apollo_instance_segmentation.json diff --git a/perception/lidar_apollo_instance_segmentation/schema/lidar_apollo_instance_segmentation.json b/perception/lidar_apollo_instance_segmentation/schema/lidar_apollo_instance_segmentation.json new file mode 100644 index 0000000000000..3a8c6e139153c --- /dev/null +++ b/perception/lidar_apollo_instance_segmentation/schema/lidar_apollo_instance_segmentation.json @@ -0,0 +1,79 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for lidar_apollo_instance_segmentation", + "type": "object", + "definitions": { + "velodyne_monitor": { + "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": ["/**"] +} diff --git a/perception/lidar_apollo_instance_segmentation/src/detector.cpp b/perception/lidar_apollo_instance_segmentation/src/detector.cpp index 5da7825f96681..9edfc783179c7 100644 --- a/perception/lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/lidar_apollo_instance_segmentation/src/detector.cpp @@ -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"); + score_threshold_ = node_->declare_parameter("score_threshold"); + range = node_->declare_parameter("range"); + width = node_->declare_parameter("width"); + height = node_->declare_parameter("height"); + onnx_file = node_->declare_parameter("onnx_file"); + use_intensity_feature = node_->declare_parameter("use_intensity_feature"); + use_constant_feature = node_->declare_parameter("use_constant_feature"); + target_frame_ = node_->declare_parameter("target_frame"); z_offset_ = node_->declare_parameter("z_offset", -2.0); - const auto precision = node_->declare_parameter("precision", "fp32"); + const auto precision = node_->declare_parameter("precision", "fp32"); trt_common_ = std::make_unique( onnx_file, precision, nullptr, tensorrt_common::BatchConfig{1, 1, 1}, 1 << 30);