Skip to content

Commit 564e8c1

Browse files
authored
feat(map_loader): add waypoints flag (autowarefoundation#7480)
* feat(map_loader): handle centelrine and waypoints Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * update README Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix doc Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * update schema Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 2165e2d commit 564e8c1

File tree

6 files changed

+26
-4
lines changed

6 files changed

+26
-4
lines changed

map/map_loader/README.md

+3
Original file line numberDiff line numberDiff line change
@@ -150,6 +150,9 @@ Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tie
150150

151151
{{ json_to_markdown("map/map_loader/schema/lanelet2_map_loader.schema.json") }}
152152

153+
`use_waypoints` decides how to handle a centerline.
154+
This flag enables to use the `overwriteLaneletsCenterlineWithWaypoints` function instead of `overwriteLaneletsCenterline`. Please see [the document of the lanelet2_extension package](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md#centerline) in detail.
155+
153156
---
154157

155158
## lanelet2_map_visualization
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
/**:
22
ros__parameters:
3-
center_line_resolution: 5.0 # [m]
3+
center_line_resolution: 5.0 # [m]
4+
use_waypoints: true # "centerline" in the Lanelet2 map will be used as a "waypoints" tag.
45
lanelet2_map_path: $(var lanelet2_map_path) # The lanelet2 map path

map/map_loader/schema/lanelet2_map_loader.schema.json

+6-1
Original file line numberDiff line numberDiff line change
@@ -11,13 +11,18 @@
1111
"description": "Resolution of the Lanelet center line [m]",
1212
"default": "5.0"
1313
},
14+
"use_waypoints": {
15+
"type": "boolean",
16+
"description": "If true, `centerline` in the Lanelet2 map will be used as a `waypoints` tag.",
17+
"default": true
18+
},
1419
"lanelet2_map_path": {
1520
"type": "string",
1621
"description": "The lanelet2 map path pointing to the .osm file",
1722
"default": ""
1823
}
1924
},
20-
"required": ["center_line_resolution", "lanelet2_map_path"],
25+
"required": ["center_line_resolution", "use_waypoints", "lanelet2_map_path"],
2126
"additionalProperties": false
2227
}
2328
},

map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -63,13 +63,15 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
6363

6464
declare_parameter<std::string>("lanelet2_map_path");
6565
declare_parameter<double>("center_line_resolution");
66+
declare_parameter<bool>("use_waypoints");
6667
}
6768

6869
void Lanelet2MapLoaderNode::on_map_projector_info(
6970
const MapProjectorInfo::Message::ConstSharedPtr msg)
7071
{
7172
const auto lanelet2_filename = get_parameter("lanelet2_map_path").as_string();
7273
const auto center_line_resolution = get_parameter("center_line_resolution").as_double();
74+
const auto use_waypoints = get_parameter("use_waypoints").as_bool();
7375

7476
// load map from file
7577
const auto map = load_map(lanelet2_filename, *msg);
@@ -79,7 +81,11 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
7981
}
8082

8183
// overwrite centerline
82-
lanelet::utils::overwriteLaneletsCenterline(map, center_line_resolution, false);
84+
if (use_waypoints) {
85+
lanelet::utils::overwriteLaneletsCenterlineWithWaypoints(map, center_line_resolution, false);
86+
} else {
87+
lanelet::utils::overwriteLaneletsCenterline(map, center_line_resolution, false);
88+
}
8389

8490
// create map bin msg
8591
const auto map_bin_msg = create_map_bin_msg(map, lanelet2_filename, now());

map/map_loader/test/lanelet2_map_loader_launch.test.py

+7-1
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,13 @@ def generate_test_description():
3434
lanelet2_map_loader = Node(
3535
package="map_loader",
3636
executable="lanelet2_map_loader",
37-
parameters=[{"lanelet2_map_path": lanelet2_map_path, "center_line_resolution": 5.0}],
37+
parameters=[
38+
{
39+
"lanelet2_map_path": lanelet2_map_path,
40+
"center_line_resolution": 5.0,
41+
"use_waypoints": True,
42+
}
43+
],
3844
)
3945

4046
context = {}

planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -374,6 +374,7 @@ void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_
374374
Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, *map_projector_info_);
375375

376376
// overwrite more dense centerline
377+
// NOTE: overwriteLaneletsCenterlineWithWaypoints is used only in real time calculation.
377378
lanelet::utils::overwriteLaneletsCenterline(map_ptr, 5.0, false);
378379

379380
// create map bin msg

0 commit comments

Comments
 (0)