Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(autoware_pointcloud_preprocessor): rework crop box parameters #8466

Merged
2 changes: 1 addition & 1 deletion sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/concatenate_data/concatenate_and_time_sync_nodelet.cpp
src/concatenate_data/concatenate_pointclouds.cpp
src/time_synchronizer/time_synchronizer_nodelet.cpp
src/crop_box_filter/crop_box_filter_nodelet.cpp
src/crop_box_filter/crop_box_filter_node.cpp
src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp
src/downsample_filter/random_downsample_filter_nodelet.cpp
src/downsample_filter/approximate_downsample_filter_nodelet.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
/**:
ros__parameters:
min_x: -1.0
min_y: -1.0
min_z: -1.0
max_x: 1.0
max_y: 1.0
max_z: 1.0
negative: false
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
input_frame: ""
output_frame: ""
max_queue_size: 5
use_indices: false
latched_indices: false
approximate_sync: false
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,7 @@ This implementation inherit `autoware::pointcloud_preprocessor::Filter` class, p

### Core Parameters

| Name | Type | Default Value | Description |
| ------- | ------ | ------------- | ----------------------------------------- |
| `min_x` | double | -1.0 | x-coordinate minimum value for crop range |
| `max_x` | double | 1.0 | x-coordinate maximum value for crop range |
| `min_y` | double | -1.0 | y-coordinate minimum value for crop range |
| `max_y` | double | 1.0 | y-coordinate maximum value for crop range |
| `min_z` | double | -1.0 | z-coordinate minimum value for crop range |
| `max_z` | double | 1.0 | z-coordinate maximum value for crop range |
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/crop_box_filter_node.schema.json") }}

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,8 @@
*
*/

#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODE_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODE_HPP_

#include "autoware/pointcloud_preprocessor/filter.hpp"
#include "autoware/pointcloud_preprocessor/transform_info.hpp"
Expand Down Expand Up @@ -104,4 +104,4 @@ class CropBoxFilterComponent : public autoware::pointcloud_preprocessor::Filter
};
} // namespace autoware::pointcloud_preprocessor

#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODE_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<launch>
<arg name="input_topic_name" default="/sensing/lidar/top/pointcloud_raw_ex"/>
<arg name="output_topic_name" default="/sensing/lidar/top/self_cropped/pointcloud_ex"/>
<arg name="input_frame" default="base_link"/>
<arg name="output_frame" default="base_link"/>
<arg name="filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/filter.param.yaml"/>
<arg name="crop_box_filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/crop_box_filter_node.param.yaml"/>
<node pkg="autoware_pointcloud_preprocessor" exec="crop_box_filter_node" name="crop_box_filter_node">
<param from="$(var crop_box_filter_param_file)"/>
<param from="$(var filter_param_file)"/>
<remap from="input" to="$(var input_topic_name)"/>
<remap from="output" to="$(var output_topic_name)"/>
<param name="input_frame" value="$(var input_frame)"/>
<param name="output_frame" value="$(var output_frame)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Crop Box Filter Node",
"type": "object",
"definitions": {
"crop_box_filter": {
"type": "object",
"properties": {
"min_x": {
"type": "number",
"description": "x-coordinate minimum value for crop range",
"default": "-1.0"
},
"min_y": {
"type": "number",
"description": "y-coordinate minimum value for crop range",
"default": "-1.0"
},
"min_z": {
"type": "number",
"description": "z-coordinate minimum value for crop range",
"default": "-1.0"
},
"max_x": {
"type": "number",
"description": "x-coordinate maximum value for crop range",
"default": "1.0"
},
"max_y": {
"type": "number",
"description": "y-coordinate maximum value for crop range",
"default": "1.0"
},
"max_z": {
"type": "number",
"description": "z-coordinate maximum value for crop range",
"default": "1.0"
},
"negative": {
"type": "boolean",
"description": "if negative then choose the point outside the box",
"default": "false"
}
},
"required": ["min_x", "min_y", "min_z", "max_x", "max_y", "max_z", "negative"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/crop_box_filter"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -49,7 +49,7 @@
*
*/

#include "autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp"
#include "autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_node.hpp"

#include <sensor_msgs/point_cloud2_iterator.hpp>

Expand All @@ -73,13 +73,13 @@ CropBoxFilterComponent::CropBoxFilterComponent(const rclcpp::NodeOptions & optio
// set initial parameters
{
auto & p = param_;
p.min_x = static_cast<float>(declare_parameter("min_x", -1.0));
p.min_y = static_cast<float>(declare_parameter("min_y", -1.0));
p.min_z = static_cast<float>(declare_parameter("min_z", -1.0));
p.max_x = static_cast<float>(declare_parameter("max_x", 1.0));
p.max_y = static_cast<float>(declare_parameter("max_y", 1.0));
p.max_z = static_cast<float>(declare_parameter("max_z", 1.0));
p.negative = static_cast<bool>(declare_parameter("negative", false));
p.min_x = declare_parameter<float>("min_x");
p.min_y = declare_parameter<float>("min_y");
p.min_z = declare_parameter<float>("min_z");
p.max_x = declare_parameter<float>("max_x");
p.max_y = declare_parameter<float>("max_y");
p.max_z = declare_parameter<float>("max_z");
p.negative = declare_parameter<bool>("negative");
if (tf_input_frame_.empty()) {
throw std::invalid_argument("Crop box requires non-empty input_frame");
}
Expand Down
Loading