Skip to content

Commit 2ecad48

Browse files
Merge pull request autowarefoundation#617 from tier4/sync-upstream
chore: sync upstream
2 parents e20856f + a3c6ea2 commit 2ecad48

File tree

66 files changed

+1256
-304
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

66 files changed

+1256
-304
lines changed

launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml

+6
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,8 @@
1010
<arg name="container_name" default="occupancy_grid_map_container"/>
1111
<arg name="occupancy_grid_map_method" description="options: pointcloud_based_occupancy_grid_map, laserscan_based_occupancy_grid_map"/>
1212
<arg name="occupancy_grid_map_param_path"/>
13+
<arg name="occupancy_grid_map_updater" description="options: binary_bayes_filter"/>
14+
<arg name="occupancy_grid_map_updater_param_path"/>
1315

1416
<!--pointcloud based method-->
1517
<group if="$(eval &quot;'$(var occupancy_grid_map_method)'=='pointcloud_based_occupancy_grid_map'&quot;)">
@@ -22,6 +24,8 @@
2224
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
2325
<arg name="container_name" value="$(var container_name)"/>
2426
<arg name="param_file" value="$(var occupancy_grid_map_param_path)"/>
27+
<arg name="updater_type" value="$(var occupancy_grid_map_updater)"/>
28+
<arg name="updater_param_file" value="$(var occupancy_grid_map_updater_param_path)"/>
2529
</include>
2630
</group>
2731

@@ -36,6 +40,8 @@
3640
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
3741
<arg name="container_name" value="$(var container_name)"/>
3842
<arg name="param_file" value="$(var occupancy_grid_map_param_path)"/>
43+
<arg name="updater_type" value="$(var occupancy_grid_map_updater)"/>
44+
<arg name="updater_param_file" value="$(var occupancy_grid_map_updater_param_path)"/>
3945
</include>
4046
</group>
4147
</launch>

launch/tier4_perception_launch/launch/perception.launch.xml

+4
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,8 @@
99
<arg name="obstacle_segmentation_ground_segmentation_elevation_map_param_path"/>
1010
<arg name="occupancy_grid_map_method"/>
1111
<arg name="occupancy_grid_map_param_path"/>
12+
<arg name="occupancy_grid_map_updater"/>
13+
<arg name="occupancy_grid_map_updater_param_path"/>
1214

1315
<!-- centerpoint model configs -->
1416
<arg name="centerpoint_model_name" default="centerpoint_tiny" description="options: `centerpoint` or `centerpoint_tiny`"/>
@@ -84,6 +86,8 @@
8486
<arg name="container_name" value="$(var pointcloud_container_name)"/>
8587
<arg name="occupancy_grid_map_method" value="$(var occupancy_grid_map_method)"/>
8688
<arg name="occupancy_grid_map_param_path" value="$(var occupancy_grid_map_param_path)"/>
89+
<arg name="occupancy_grid_map_updater" value="$(var occupancy_grid_map_updater)"/>
90+
<arg name="occupancy_grid_map_updater_param_path" value="$(var occupancy_grid_map_updater_param_path)"/>
8791
</include>
8892
</group>
8993

launch/tier4_simulator_launch/launch/simulator.launch.xml

+4
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,8 @@
33
<arg name="fault_injection_param_path"/>
44
<arg name="obstacle_segmentation_ground_segmentation_elevation_map_param_path"/>
55
<arg name="laserscan_based_occupancy_grid_map_param_path"/>
6+
<arg name="occupancy_grid_map_updater"/>
7+
<arg name="occupancy_grid_map_updater_param_path"/>
68
<arg name="pose_initializer_param_path"/>
79
<arg name="pose_initializer_common_param_path"/>
810

@@ -49,6 +51,8 @@
4951
<arg name="output" value="/perception/occupancy_grid_map/map"/>
5052
<arg name="occupancy_grid_map_method" value="laserscan_based_occupancy_grid_map"/>
5153
<arg name="occupancy_grid_map_param_path" value="$(var laserscan_based_occupancy_grid_map_param_path)"/>
54+
<arg name="occupancy_grid_map_updater" value="$(var occupancy_grid_map_updater)"/>
55+
<arg name="occupancy_grid_map_updater_param_path" value="$(var occupancy_grid_map_updater_param_path)"/>
5256
</include>
5357
</group>
5458

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
/**:
2+
ros__parameters:
3+
binary_bayes_filter:
4+
probability_matrix:
5+
occupied_to_occupied: 0.95
6+
occupied_to_free: 0.05
7+
free_to_occupied: 0.2
8+
free_to_free: 0.8
9+
v_ratio: 10.0

perception/probabilistic_occupancy_grid_map/config/laserscan_based_occupancy_grid_map.param.yaml

+5-1
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,11 @@
77
# ray-tracing center: main sensor frame is preferable like: "velodyne_top"
88
scan_origin_frame: "base_link"
99

10-
use_height_filter: true
10+
height_filter:
11+
use_height_filter: true
12+
min_height: -1.0
13+
max_height: 2.0
14+
1115
enable_single_frame_mode: false
1216
map_length: 100.0
1317
map_width: 100.0

perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml

+5-1
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,11 @@
33
map_length: 100.0 # [m]
44
map_resolution: 0.5 # [m]
55

6-
use_height_filter: true
6+
height_filter:
7+
use_height_filter: true
8+
min_height: -1.0
9+
max_height: 2.0
10+
711
enable_single_frame_mode: false
812
# use sensor pointcloud to filter obstacle pointcloud
913
filter_obstacle_pointcloud_by_raw_pointcloud: false

perception/probabilistic_occupancy_grid_map/include/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,8 @@ class LaserscanBasedOccupancyGridMapNode : public rclcpp::Node
9595
std::string gridmap_origin_frame_;
9696
std::string scan_origin_frame_;
9797
bool use_height_filter_;
98+
double min_height_;
99+
double max_height_;
98100
bool enable_single_frame_mode_;
99101
};
100102

perception/probabilistic_occupancy_grid_map/include/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,8 @@ class PointcloudBasedOccupancyGridMapNode : public rclcpp::Node
8585
std::string gridmap_origin_frame_;
8686
std::string scan_origin_frame_;
8787
bool use_height_filter_;
88+
double min_height_;
89+
double max_height_;
8890
bool enable_single_frame_mode_;
8991
bool filter_obstacle_pointcloud_by_raw_pointcloud_;
9092
};

perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp

+3-9
Original file line numberDiff line numberDiff line change
@@ -27,20 +27,14 @@ class OccupancyGridMapBBFUpdater : public OccupancyGridMapUpdaterInterface
2727
public:
2828
enum Index : size_t { OCCUPIED = 0U, FREE = 1U };
2929
OccupancyGridMapBBFUpdater(
30-
const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution)
31-
: OccupancyGridMapUpdaterInterface(cells_size_x, cells_size_y, resolution)
32-
{
33-
probability_matrix_(Index::OCCUPIED, Index::OCCUPIED) = 0.95;
34-
probability_matrix_(Index::FREE, Index::OCCUPIED) =
35-
1.0 - probability_matrix_(OCCUPIED, OCCUPIED);
36-
probability_matrix_(Index::FREE, Index::FREE) = 0.8;
37-
probability_matrix_(Index::OCCUPIED, Index::FREE) = 1.0 - probability_matrix_(FREE, FREE);
38-
}
30+
const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution);
3931
bool update(const Costmap2D & single_frame_occupancy_grid_map) override;
32+
void initRosParam(rclcpp::Node & node) override;
4033

4134
private:
4235
inline unsigned char applyBBF(const unsigned char & z, const unsigned char & o);
4336
Eigen::Matrix2f probability_matrix_;
37+
double v_ratio_;
4438
};
4539

4640
} // namespace costmap_2d

perception/probabilistic_occupancy_grid_map/include/updater/occupancy_grid_map_updater_interface.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "cost_value.hpp"
1919

2020
#include <nav2_costmap_2d/costmap_2d.hpp>
21+
#include <rclcpp/node.hpp>
2122

2223
namespace costmap_2d
2324
{
@@ -32,6 +33,7 @@ class OccupancyGridMapUpdaterInterface : public nav2_costmap_2d::Costmap2D
3233
}
3334
virtual ~OccupancyGridMapUpdaterInterface() = default;
3435
virtual bool update(const Costmap2D & single_frame_occupancy_grid_map) = 0;
36+
virtual void initRosParam(rclcpp::Node & node) = 0;
3537
};
3638

3739
} // namespace costmap_2d

perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py

+34-25
Original file line numberDiff line numberDiff line change
@@ -26,35 +26,34 @@
2626
import yaml
2727

2828

29-
def overwrite_config(param_dict, launch_config_name, node_params_name, context):
30-
if LaunchConfiguration(launch_config_name).perform(context) != "":
31-
param_dict[node_params_name] = LaunchConfiguration(launch_config_name).perform(context)
32-
33-
3429
def launch_setup(context, *args, **kwargs):
3530
# load parameter files
3631
param_file = LaunchConfiguration("param_file").perform(context)
3732
with open(param_file, "r") as f:
3833
laserscan_based_occupancy_grid_map_node_params = yaml.safe_load(f)["/**"]["ros__parameters"]
39-
overwrite_config(
40-
laserscan_based_occupancy_grid_map_node_params,
41-
"map_origin",
42-
"gridmap_origin_frame",
43-
context,
44-
)
45-
overwrite_config(
46-
laserscan_based_occupancy_grid_map_node_params, "scan_origin", "scan_origin_frame", context
47-
)
34+
35+
updater_param_file = LaunchConfiguration("updater_param_file").perform(context)
36+
with open(updater_param_file, "r") as f:
37+
occupancy_grid_map_updater_params = yaml.safe_load(f)["/**"]["ros__parameters"]
4838

4939
composable_nodes = [
5040
ComposableNode(
5141
package="pointcloud_to_laserscan",
5242
plugin="pointcloud_to_laserscan::PointCloudToLaserScanNode",
5343
name="pointcloud_to_laserscan_node",
5444
remappings=[
55-
("~/input/pointcloud", LaunchConfiguration("input/obstacle_pointcloud")),
56-
("~/output/laserscan", LaunchConfiguration("output/laserscan")),
57-
("~/output/pointcloud", LaunchConfiguration("output/pointcloud")),
45+
(
46+
"~/input/pointcloud",
47+
LaunchConfiguration("input/obstacle_pointcloud"),
48+
),
49+
(
50+
"~/output/laserscan",
51+
LaunchConfiguration("output/laserscan"),
52+
),
53+
(
54+
"~/output/pointcloud",
55+
LaunchConfiguration("output/pointcloud"),
56+
),
5857
("~/output/ray", LaunchConfiguration("output/ray")),
5958
("~/output/stixel", LaunchConfiguration("output/stixel")),
6059
],
@@ -90,12 +89,19 @@ def launch_setup(context, *args, **kwargs):
9089
name="occupancy_grid_map_node",
9190
remappings=[
9291
("~/input/laserscan", LaunchConfiguration("output/laserscan")),
93-
("~/input/obstacle_pointcloud", LaunchConfiguration("input/obstacle_pointcloud")),
94-
("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")),
92+
(
93+
"~/input/obstacle_pointcloud",
94+
LaunchConfiguration("input/obstacle_pointcloud"),
95+
),
96+
(
97+
"~/input/raw_pointcloud",
98+
LaunchConfiguration("input/raw_pointcloud"),
99+
),
95100
("~/output/occupancy_grid_map", LaunchConfiguration("output")),
96101
],
97102
parameters=[
98103
laserscan_based_occupancy_grid_map_node_params,
104+
occupancy_grid_map_updater_params,
99105
{
100106
"input_obstacle_pointcloud": LaunchConfiguration("input_obstacle_pointcloud"),
101107
"input_obstacle_and_raw_pointcloud": LaunchConfiguration(
@@ -148,24 +154,27 @@ def add_launch_arg(name: str, default_value=None):
148154
add_launch_arg("use_intra_process", "false"),
149155
add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"),
150156
add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"),
151-
add_launch_arg("map_origin", "base_link"),
152-
add_launch_arg("sensor_origin", "base_link"),
153157
add_launch_arg("output", "occupancy_grid"),
154158
add_launch_arg("output/laserscan", "virtual_scan/laserscan"),
155159
add_launch_arg("output/pointcloud", "virtual_scan/pointcloud"),
156160
add_launch_arg("output/ray", "virtual_scan/ray"),
157161
add_launch_arg("output/stixel", "virtual_scan/stixel"),
158-
add_launch_arg("input_obstacle_pointcloud", "false"),
159-
add_launch_arg("input_obstacle_and_raw_pointcloud", "true"),
160162
add_launch_arg(
161163
"param_file",
162164
get_package_share_directory("probabilistic_occupancy_grid_map")
163165
+ "/config/laserscan_based_occupancy_grid_map.param.yaml",
164166
),
167+
add_launch_arg(
168+
"updater_type",
169+
"binary_bayes_filter",
170+
),
171+
add_launch_arg(
172+
"updater_param_file",
173+
get_package_share_directory("probabilistic_occupancy_grid_map")
174+
+ "/config/updater.param.yaml",
175+
),
165176
add_launch_arg("use_pointcloud_container", "false"),
166177
add_launch_arg("container_name", "occupancy_grid_map_container"),
167-
add_launch_arg("map_origin", ""),
168-
add_launch_arg("scan_origin", ""),
169178
set_container_executable,
170179
set_container_mt_executable,
171180
]

perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py

+25-14
Original file line numberDiff line numberDiff line change
@@ -38,27 +38,31 @@ def launch_setup(context, *args, **kwargs):
3838
pointcloud_based_occupancy_grid_map_node_params = yaml.safe_load(f)["/**"][
3939
"ros__parameters"
4040
]
41-
overwrite_config(
42-
pointcloud_based_occupancy_grid_map_node_params,
43-
"map_origin",
44-
"gridmap_origin_frame",
45-
context,
46-
)
47-
overwrite_config(
48-
pointcloud_based_occupancy_grid_map_node_params, "scan_origin", "scan_origin_frame", context
49-
)
41+
42+
updater_param_file = LaunchConfiguration("updater_param_file").perform(context)
43+
with open(updater_param_file, "r") as f:
44+
occupancy_grid_map_updater_params = yaml.safe_load(f)["/**"]["ros__parameters"]
5045

5146
composable_nodes = [
5247
ComposableNode(
5348
package="probabilistic_occupancy_grid_map",
5449
plugin="occupancy_grid_map::PointcloudBasedOccupancyGridMapNode",
5550
name="occupancy_grid_map_node",
5651
remappings=[
57-
("~/input/obstacle_pointcloud", LaunchConfiguration("input/obstacle_pointcloud")),
58-
("~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud")),
52+
(
53+
"~/input/obstacle_pointcloud",
54+
LaunchConfiguration("input/obstacle_pointcloud"),
55+
),
56+
(
57+
"~/input/raw_pointcloud",
58+
LaunchConfiguration("input/raw_pointcloud"),
59+
),
5960
("~/output/occupancy_grid_map", LaunchConfiguration("output")),
6061
],
61-
parameters=[pointcloud_based_occupancy_grid_map_node_params],
62+
parameters=[
63+
pointcloud_based_occupancy_grid_map_node_params,
64+
occupancy_grid_map_updater_params,
65+
],
6266
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
6367
),
6468
]
@@ -112,8 +116,15 @@ def add_launch_arg(name: str, default_value=None):
112116
get_package_share_directory("probabilistic_occupancy_grid_map")
113117
+ "/config/pointcloud_based_occupancy_grid_map.param.yaml",
114118
),
115-
add_launch_arg("map_origin", ""),
116-
add_launch_arg("scan_origin", ""),
119+
add_launch_arg(
120+
"updater_type",
121+
"binary_bayes_filter",
122+
),
123+
add_launch_arg(
124+
"updater_param_file",
125+
get_package_share_directory("probabilistic_occupancy_grid_map")
126+
+ "/config/updater.param.yaml",
127+
),
117128
set_container_executable,
118129
set_container_mt_executable,
119130
]

perception/probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp

+29-18
Original file line numberDiff line numberDiff line change
@@ -51,18 +51,20 @@ LaserscanBasedOccupancyGridMapNode::LaserscanBasedOccupancyGridMapNode(
5151
using std::placeholders::_3;
5252

5353
/* params */
54-
map_frame_ = declare_parameter("map_frame", "map");
55-
base_link_frame_ = declare_parameter("base_link_frame", "base_link");
56-
gridmap_origin_frame_ = declare_parameter("gridmap_origin_frame", "base_link");
57-
scan_origin_frame_ = declare_parameter("scan_origin_frame", "base_link");
58-
use_height_filter_ = declare_parameter("use_height_filter", true);
59-
enable_single_frame_mode_ = declare_parameter("enable_single_frame_mode", false);
60-
const double map_length{declare_parameter("map_length", 100.0)};
61-
const double map_width{declare_parameter("map_width", 100.0)};
62-
const double map_resolution{declare_parameter("map_resolution", 0.5)};
63-
const bool input_obstacle_pointcloud{declare_parameter("input_obstacle_pointcloud", true)};
64-
const bool input_obstacle_and_raw_pointcloud{
65-
declare_parameter("input_obstacle_and_raw_pointcloud", true)};
54+
map_frame_ = this->declare_parameter<std::string>("map_frame");
55+
base_link_frame_ = this->declare_parameter<std::string>("base_link_frame");
56+
gridmap_origin_frame_ = this->declare_parameter<std::string>("gridmap_origin_frame");
57+
scan_origin_frame_ = this->declare_parameter<std::string>("scan_origin_frame");
58+
use_height_filter_ = this->declare_parameter<bool>("height_filter.use_height_filter");
59+
min_height_ = this->declare_parameter<double>("height_filter.min_height");
60+
max_height_ = this->declare_parameter<double>("height_filter.max_height");
61+
enable_single_frame_mode_ = this->declare_parameter<bool>("enable_single_frame_mode");
62+
const double map_length = this->declare_parameter<double>("map_length");
63+
const double map_width = this->declare_parameter<double>("map_width");
64+
const double map_resolution = this->declare_parameter<double>("map_resolution");
65+
const bool input_obstacle_pointcloud = this->declare_parameter<bool>("input_obstacle_pointcloud");
66+
const bool input_obstacle_and_raw_pointcloud =
67+
this->declare_parameter<bool>("input_obstacle_and_raw_pointcloud");
6668

6769
/* Subscriber and publisher */
6870
laserscan_sub_.subscribe(
@@ -90,9 +92,19 @@ LaserscanBasedOccupancyGridMapNode::LaserscanBasedOccupancyGridMapNode(
9092
_3));
9193
occupancy_grid_map_pub_ = create_publisher<OccupancyGrid>("~/output/occupancy_grid_map", 1);
9294

93-
/* Occupancy grid */
94-
occupancy_grid_map_updater_ptr_ = std::make_shared<OccupancyGridMapBBFUpdater>(
95-
map_length / map_resolution, map_width / map_resolution, map_resolution);
95+
const std::string updater_type = this->declare_parameter<std::string>("updater_type");
96+
if (updater_type == "binary_bayes_filter") {
97+
occupancy_grid_map_updater_ptr_ = std::make_shared<OccupancyGridMapBBFUpdater>(
98+
map_length / map_resolution, map_width / map_resolution, map_resolution);
99+
} else {
100+
RCLCPP_WARN(
101+
get_logger(),
102+
"specified occupancy grid map updater type [%s] is not found, use binary_bayes_filter",
103+
updater_type.c_str());
104+
occupancy_grid_map_updater_ptr_ = std::make_shared<OccupancyGridMapBBFUpdater>(
105+
map_length / map_resolution, map_width / map_resolution, map_resolution);
106+
}
107+
occupancy_grid_map_updater_ptr_->initRosParam(*this);
96108
}
97109

98110
PointCloud2::SharedPtr LaserscanBasedOccupancyGridMapNode::convertLaserscanToPointCLoud2(
@@ -132,14 +144,13 @@ void LaserscanBasedOccupancyGridMapNode::onLaserscanPointCloud2WithObstacleAndRa
132144
PointCloud2 cropped_obstacle_pc{};
133145
PointCloud2 cropped_raw_pc{};
134146
if (use_height_filter_) {
135-
constexpr float min_height = -1.0, max_height = 2.0;
136147
if (!utils::cropPointcloudByHeight(
137-
*input_obstacle_msg, *tf2_, base_link_frame_, min_height, max_height,
148+
*input_obstacle_msg, *tf2_, base_link_frame_, min_height_, max_height_,
138149
cropped_obstacle_pc)) {
139150
return;
140151
}
141152
if (!utils::cropPointcloudByHeight(
142-
*input_raw_msg, *tf2_, base_link_frame_, min_height, max_height, cropped_raw_pc)) {
153+
*input_raw_msg, *tf2_, base_link_frame_, min_height_, max_height_, cropped_raw_pc)) {
143154
return;
144155
}
145156
}

0 commit comments

Comments
 (0)