From b02d2e3a60580a8e0d8f61e6177bf65f0444e424 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 6 Jun 2024 17:30:55 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../schema/centerpoint.schema.json | 239 +++++++++--------- perception/lidar_centerpoint_tvm/src/node.cpp | 5 +- .../src/single_inference_node.cpp | 4 +- 3 files changed, 123 insertions(+), 125 deletions(-) diff --git a/perception/lidar_centerpoint_tvm/schema/centerpoint.schema.json b/perception/lidar_centerpoint_tvm/schema/centerpoint.schema.json index d4f9f2f3a8092..43c956eaca061 100644 --- a/perception/lidar_centerpoint_tvm/schema/centerpoint.schema.json +++ b/perception/lidar_centerpoint_tvm/schema/centerpoint.schema.json @@ -1,129 +1,128 @@ { - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "Parameters for Lidar Centerpoint TVM Node", - "type": "object", - "definitions": { - "centerpoint": { - "type": "object", - "properties": { - "class_names": { - "type": "array", - "description": "List of class names for object detection.", - "items": { - "type": "string" - }, - "default": ["CAR", "PEDESTRIAN", "BICYCLE"] - }, - "rename_car_to_truck_and_bus": { - "type": "boolean", - "description": "Flag to rename car detections to truck and bus.", - "default": true + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Lidar Centerpoint TVM Node", + "type": "object", + "definitions": { + "centerpoint": { + "type": "object", + "properties": { + "class_names": { + "type": "array", + "description": "List of class names for object detection.", + "items": { + "type": "string" }, - "point_feature_size": { - "type": "integer", - "description": "The size of the point features.", - "default": 4 + "default": ["CAR", "PEDESTRIAN", "BICYCLE"] + }, + "rename_car_to_truck_and_bus": { + "type": "boolean", + "description": "Flag to rename car detections to truck and bus.", + "default": true + }, + "point_feature_size": { + "type": "integer", + "description": "The size of the point features.", + "default": 4 + }, + "max_voxel_size": { + "type": "integer", + "description": "The maximum number of voxels.", + "default": 40000 + }, + "point_cloud_range": { + "type": "array", + "description": "The range of the point cloud.", + "items": { + "type": "number" }, - "max_voxel_size": { - "type": "integer", - "description": "The maximum number of voxels.", - "default": 40000 + "default": [-89.6, -89.6, -3.0, 89.6, 89.6, 5.0] + }, + "voxel_size": { + "type": "array", + "description": "The size of the voxels.", + "items": { + "type": "number" }, - "point_cloud_range": { - "type": "array", - "description": "The range of the point cloud.", - "items": { - "type": "number" + "default": [0.32, 0.32, 8.0] + }, + "downsample_factor": { + "type": "integer", + "description": "The factor by which to downsample the point cloud.", + "default": 1 + }, + "encoder_in_feature_size": { + "type": "integer", + "description": "The size of the input features for the encoder.", + "default": 9 + }, + "has_twist": { + "type": "boolean", + "description": "Flag to indicate if the twist (velocity) is included.", + "default": false + }, + "post_process_params": { + "type": "object", + "properties": { + "circle_nms_dist_threshold": { + "type": "number", + "description": "The distance threshold for circle NMS.", + "default": 1.5 }, - "default": [-89.6, -89.6, -3.0, 89.6, 89.6, 5.0] - }, - "voxel_size": { - "type": "array", - "description": "The size of the voxels.", - "items": { - "type": "number" + "score_threshold": { + "type": "number", + "description": "Detected objects with score less than threshold are ignored.", + "default": 0.35 }, - "default": [0.32, 0.32, 8.0] - }, - "downsample_factor": { - "type": "integer", - "description": "The factor by which to downsample the point cloud.", - "default": 1 - }, - "encoder_in_feature_size": { - "type": "integer", - "description": "The size of the input features for the encoder.", - "default": 9 - }, - "has_twist": { - "type": "boolean", - "description": "Flag to indicate if the twist (velocity) is included.", - "default": false + "yaw_norm_threshold": { + "type": "number", + "description": "The threshold for yaw normalization.", + "default": 0.0 + } }, - "post_process_params": { - "type": "object", - "properties": { - "circle_nms_dist_threshold": { - "type": "number", - "description": "The distance threshold for circle NMS.", - "default": 1.5 - }, - "score_threshold": { - "type": "number", - "description": "Detected objects with score less than threshold are ignored.", - "default": 0.35 - }, - "yaw_norm_threshold": { - "type": "number", - "description": "The threshold for yaw normalization.", - "default": 0.0 - } + "required": ["circle_nms_dist_threshold", "score_threshold", "yaw_norm_threshold"] + }, + "densification_params": { + "type": "object", + "properties": { + "world_frame_id": { + "type": "string", + "description": "The world frame id to fuse multi-frame pointcloud.", + "default": "map" }, - "required": ["circle_nms_dist_threshold", "score_threshold", "yaw_norm_threshold"] + "num_past_frames": { + "type": "integer", + "description": "The number of past frames to fuse with the current frame.", + "default": 1 + } }, - "densification_params": { - "type": "object", - "properties": { - "world_frame_id": { - "type": "string", - "description": "The world frame id to fuse multi-frame pointcloud.", - "default": "map" - }, - "num_past_frames": { - "type": "integer", - "description": "The number of past frames to fuse with the current frame.", - "default": 1 - } - }, - "required": ["world_frame_id", "num_past_frames"] - } - }, - "required": [ - "class_names", - "rename_car_to_truck_and_bus", - "point_feature_size", - "max_voxel_size", - "point_cloud_range", - "voxel_size", - "downsample_factor", - "encoder_in_feature_size", - "has_twist", - "post_process_params", - "densification_params" - ] - } - }, - "properties": { - "/**": { - "type": "object", - "properties": { - "ros__parameters": { - "$ref": "#/definitions/centerpoint" - } - }, - "required": ["ros__parameters"] - } - }, - "required": ["/**"] - } - \ No newline at end of file + "required": ["world_frame_id", "num_past_frames"] + } + }, + "required": [ + "class_names", + "rename_car_to_truck_and_bus", + "point_feature_size", + "max_voxel_size", + "point_cloud_range", + "voxel_size", + "downsample_factor", + "encoder_in_feature_size", + "has_twist", + "post_process_params", + "densification_params" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/centerpoint" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/lidar_centerpoint_tvm/src/node.cpp b/perception/lidar_centerpoint_tvm/src/node.cpp index d847274b8c0d3..aecd65eee5567 100644 --- a/perception/lidar_centerpoint_tvm/src/node.cpp +++ b/perception/lidar_centerpoint_tvm/src/node.cpp @@ -42,8 +42,8 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod { const float score_threshold = static_cast(this->declare_parameter("post_process_params.score_threshold")); - const float circle_nms_dist_threshold = - static_cast(this->declare_parameter("post_process_params.circle_nms_dist_threshold")); + const float circle_nms_dist_threshold = static_cast( + this->declare_parameter("post_process_params.circle_nms_dist_threshold")); const float yaw_norm_threshold = static_cast(this->declare_parameter("post_process_params.yaw_norm_threshold")); const std::string densification_world_frame_id = @@ -55,7 +55,6 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod rename_car_to_truck_and_bus_ = this->declare_parameter("rename_car_to_truck_and_bus"); has_twist_ = this->declare_parameter("has_twist"); - class_names_ = this->declare_parameter>("class_names"); rename_car_to_truck_and_bus_ = this->declare_parameter("rename_car_to_truck_and_bus", false); has_twist_ = this->declare_parameter("has_twist", false); diff --git a/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp b/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp index bfe4ef607bfa6..6be59d5efe541 100644 --- a/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp +++ b/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp @@ -47,8 +47,8 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode( { const float score_threshold = static_cast(this->declare_parameter("post_process_params.score_threshold")); - const float circle_nms_dist_threshold = - static_cast(this->declare_parameter("post_process_params.circle_nms_dist_threshold")); + const float circle_nms_dist_threshold = static_cast( + this->declare_parameter("post_process_params.circle_nms_dist_threshold")); const float yaw_norm_threshold = static_cast(this->declare_parameter("post_process_params.yaw_norm_threshold")); const std::string densification_world_frame_id =