Skip to content

Commit af4df4b

Browse files
committed
add param and schema file, edit readme
Signed-off-by: oguzkaganozt <oguzkaganozt@gmail.com>
1 parent 41aab51 commit af4df4b

5 files changed

+113
-22
lines changed

perception/occupancy_grid_map_outlier_filter/CMakeLists.txt

+4-1
Original file line numberDiff line numberDiff line change
@@ -44,4 +44,7 @@ rclcpp_components_register_node(occupancy_grid_map_outlier_filter
4444
PLUGIN "occupancy_grid_map_outlier_filter::OccupancyGridMapOutlierFilterComponent"
4545
EXECUTABLE occupancy_grid_map_outlier_filter_node)
4646

47-
ament_auto_package(INSTALL_TO_SHARE)
47+
ament_auto_package(
48+
INSTALL_TO_SHARE
49+
config
50+
)

perception/occupancy_grid_map_outlier_filter/README.md

+1-11
Original file line numberDiff line numberDiff line change
@@ -40,17 +40,7 @@ The following video is a sample. Yellow points are high occupancy probability, g
4040

4141
## Parameters
4242

43-
| Name | Type | Description |
44-
| ------------------------------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
45-
| `map_frame` | string | map frame id |
46-
| `base_link_frame` | string | base link frame id |
47-
| `cost_threshold` | int | Cost threshold of occupancy grid map (0~100). 100 means 100% probability that there is an obstacle, close to 50 means that it is indistinguishable whether it is an obstacle or free space, 0 means that there is no obstacle. |
48-
| `enable_debugger` | bool | Whether to output the point cloud for debugging. |
49-
| `use_radius_search_2d_filter` | bool | Whether or not to apply density-based outlier filters to objects that are judged to have low probability of occupancy on the occupancy grid map. |
50-
| `radius_search_2d_filter/search_radius` | float | Radius when calculating the density |
51-
| `radius_search_2d_filter/min_points_and_distance_ratio` | float | Threshold value of the number of point clouds per radius when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink. |
52-
| `radius_search_2d_filter/min_points` | int | Minimum number of point clouds per radius |
53-
| `radius_search_2d_filter/max_points` | int | Maximum number of point clouds per radius |
43+
{{ json_to_markdown("perception/occupancy_grid_map_outlier_filter/schema/occupancy_grid_map_outlier_filter.schema.json") }}
5444

5545
## Assumptions / Known limits
5646

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
/**:
2+
ros__parameters:
3+
radius_search_2d_filter.search_radius: 1.0f
4+
radius_search_2d_filter.min_points_and_distance_ratio: 400.0f
5+
radius_search_2d_filter.min_points: 4
6+
radius_search_2d_filter.max_points: 70
7+
radius_search_2d_filter.max_filter_points_nb: 15000
8+
map_frame: "map"
9+
base_link_frame: "base_link"
10+
cost_threshold: 45
11+
use_radius_search_2d_filter: true
12+
enable_debugger: false
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,86 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for occupancy_grid_map_outlier",
4+
"type": "object",
5+
"definitions": {
6+
"occupancy_grid_map_outlier": {
7+
"type": "object",
8+
"properties": {
9+
"radius_search_2d_filter.search_radius": {
10+
"type": "number",
11+
"default": 1.0,
12+
"description": "Radius when calculating the density"
13+
},
14+
"radius_search_2d_filter.min_points_and_distance_ratio": {
15+
"type": "number",
16+
"default": 400.0,
17+
"description": "Threshold value of the number of point clouds per radius when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink"
18+
},
19+
"radius_search_2d_filter.min_points": {
20+
"type": "number",
21+
"default": 4,
22+
"description": "Minimum number of point clouds per radius"
23+
},
24+
"radius_search_2d_filter.max_points": {
25+
"type": "number",
26+
"default": 70,
27+
"description": "Maximum number of point clouds per radius"
28+
},
29+
"radius_search_2d_filter.max_filter_points_nb": {
30+
"type": "number",
31+
"default": 15000,
32+
"description": "Maximum number of point clouds to be filtered"
33+
},
34+
"map_frame": {
35+
"type": "string",
36+
"default": "map",
37+
"description": "map frame id"
38+
},
39+
"base_link_frame": {
40+
"type": "string",
41+
"default": "base_link",
42+
"description": "base link frame id"
43+
},
44+
"cost_threshold": {
45+
"type": "number",
46+
"default": 45,
47+
"description": "Cost threshold of occupancy grid map (0~100). 100 means 100% probability that there is an obstacle, close to 50 means that it is indistinguishable whether it is an obstacle or free space, 0 means that there is no obstacle"
48+
},
49+
"use_radius_search_2d_filter": {
50+
"type": "boolean",
51+
"default": true,
52+
"description": "Whether or not to apply density-based outlier filters to objects that are judged to have low probability of occupancy on the occupancy grid map"
53+
},
54+
"enable_debugger": {
55+
"type": "boolean",
56+
"default": false,
57+
"description": "Whether to output the point cloud for debugging"
58+
}
59+
},
60+
"required": [
61+
"radius_search_2d_filter.search_radius",
62+
"radius_search_2d_filter.min_points_and_distance_ratio",
63+
"radius_search_2d_filter.min_points",
64+
"radius_search_2d_filter.max_points",
65+
"radius_search_2d_filter.max_filter_points_nb",
66+
"map_frame",
67+
"base_link_frame",
68+
"cost_threshold",
69+
"use_radius_search_2d_filter",
70+
"enable_debugger"
71+
]
72+
}
73+
},
74+
"properties": {
75+
"/**": {
76+
"type": "object",
77+
"properties": {
78+
"ros__parameters": {
79+
"$ref": "#/definitions/occupancy_grid_map_outlier"
80+
}
81+
},
82+
"required": ["ros__parameters"]
83+
}
84+
},
85+
"required": ["/**"]
86+
}

perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp

+10-10
Original file line numberDiff line numberDiff line change
@@ -105,13 +105,13 @@ namespace occupancy_grid_map_outlier_filter
105105
{
106106
RadiusSearch2dFilter::RadiusSearch2dFilter(rclcpp::Node & node)
107107
{
108-
search_radius_ = node.declare_parameter("radius_search_2d_filter.search_radius", 1.0f);
108+
search_radius_ = node.declare_parameter<float>("radius_search_2d_filter.search_radius");
109109
min_points_and_distance_ratio_ =
110-
node.declare_parameter("radius_search_2d_filter.min_points_and_distance_ratio", 400.0f);
111-
min_points_ = node.declare_parameter("radius_search_2d_filter.min_points", 4);
112-
max_points_ = node.declare_parameter("radius_search_2d_filter.max_points", 70);
110+
node.declare_parameter<float>("radius_search_2d_filter.min_points_and_distance_ratio");
111+
min_points_ = node.declare_parameter<int>("radius_search_2d_filter.min_points");
112+
max_points_ = node.declare_parameter<int>("radius_search_2d_filter.max_points", 70);
113113
max_filter_points_nb_ =
114-
node.declare_parameter("radius_search_2d_filter.max_filter_points_nb", 15000);
114+
node.declare_parameter<int>("radius_search_2d_filter.max_filter_points_nb", 15000);
115115
kd_tree_ = pcl::make_shared<pcl::search::KdTree<pcl::PointXY>>(false);
116116
}
117117

@@ -206,11 +206,11 @@ OccupancyGridMapOutlierFilterComponent::OccupancyGridMapOutlierFilterComponent(
206206
}
207207

208208
/* params */
209-
map_frame_ = declare_parameter("map_frame", "map");
210-
base_link_frame_ = declare_parameter("base_link_frame", "base_link");
211-
cost_threshold_ = declare_parameter("cost_threshold", 45);
212-
auto use_radius_search_2d_filter = declare_parameter("use_radius_search_2d_filter", true);
213-
auto enable_debugger = declare_parameter("enable_debugger", false);
209+
map_frame_ = declare_parameter<std::string>("map_frame");
210+
base_link_frame_ = declare_parameter<std::string>("base_link_frame");
211+
cost_threshold_ = declare_parameter<int>("cost_threshold");
212+
auto use_radius_search_2d_filter = declare_parameter<bool>("use_radius_search_2d_filter");
213+
auto enable_debugger = declare_parameter<bool>("enable_debugger");
214214

215215
/* tf */
216216
tf2_ = std::make_shared<tf2_ros::Buffer>(get_clock());

0 commit comments

Comments
 (0)