Skip to content

Commit 4127774

Browse files
soblinsasakisasaki
andauthored
feat(autoware_trajectory): implement a function to construct trajectory class for reference path (#469)
Signed-off-by: Mamoru Sobue <[email protected]> Co-authored-by: Junya Sasaki <[email protected]>
1 parent 2aced4d commit 4127774

File tree

31 files changed

+10366
-141
lines changed

31 files changed

+10366
-141
lines changed

common/autoware_lanelet2_utils/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
99
src/topology.cpp
1010
src/stop_line.cpp
1111
src/intersection.cpp
12+
src/conversion.cpp
1213
src/geometry.cpp
1314
)
1415

Lines changed: 46 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,46 @@
1+
// Copyright 2025 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef AUTOWARE__LANELET2_UTILS__CONVERSION_HPP_
16+
#define AUTOWARE__LANELET2_UTILS__CONVERSION_HPP_
17+
18+
#include <lanelet2_core/Forward.h>
19+
#include <lanelet2_routing/Forward.h>
20+
#include <lanelet2_traffic_rules/TrafficRulesFactory.h>
21+
22+
#include <string>
23+
#include <utility>
24+
25+
namespace autoware::experimental::lanelet2_utils
26+
{
27+
28+
/**
29+
* @brief load a map file from the given path and return LaneletMap object
30+
*/
31+
lanelet::LaneletMapConstPtr load_mgrs_coordinate_map(
32+
const std::string & path, const double centerline_resolution = 5.0);
33+
34+
/**
35+
* @brief instantiate RoutingGraph from given LaneletMap only from "road" lanes
36+
* @param location [in, opt, lanelet::Locations::Germany] location value
37+
* @param participant [in, opt, lanelet::Participants::Vehicle] participant value
38+
* @return RoutingGraph object without road_shoulder and bicycle_lane, and traffic rule object
39+
*/
40+
std::pair<lanelet::routing::RoutingGraphConstPtr, lanelet::traffic_rules::TrafficRulesPtr>
41+
instantiate_routing_graph_and_traffic_rules(
42+
lanelet::LaneletMapConstPtr lanelet_map, const char * location = lanelet::Locations::Germany,
43+
const char * participant = lanelet::Participants::Vehicle);
44+
45+
} // namespace autoware::experimental::lanelet2_utils
46+
#endif // AUTOWARE__LANELET2_UTILS__CONVERSION_HPP_

common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/geometry.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222

2323
#include <optional>
2424

25-
namespace autoware::lanelet2_utils
25+
namespace autoware::experimental::lanelet2_utils
2626
{
2727

2828
/**
@@ -100,6 +100,6 @@ std::optional<lanelet::LineString3d> get_linestring_from_arc_length(
100100
std::optional<geometry_msgs::msg::Pose> get_pose_from_2d_arc_length(
101101
const lanelet::ConstLanelets & lanelet_sequence, const double s);
102102

103-
} // namespace autoware::lanelet2_utils
103+
} // namespace autoware::experimental::lanelet2_utils
104104

105105
#endif // AUTOWARE__LANELET2_UTILS__GEOMETRY_HPP_

common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/topology.hpp

Lines changed: 0 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -24,16 +24,6 @@
2424

2525
namespace autoware::experimental::lanelet2_utils
2626
{
27-
/**
28-
* @brief instantiate RoutingGraph from given LaneletMap only from "road" lanes
29-
* @param location [in, opt, lanelet::Locations::Germany] location value
30-
* @param participant [in, opt, lanelet::Participants::Vehicle] participant value
31-
* @return RoutingGraph object without road_shoulder and bicycle_lane
32-
*/
33-
lanelet::routing::RoutingGraphConstPtr instantiate_routing_graph(
34-
lanelet::LaneletMapConstPtr lanelet_map, const char * location = lanelet::Locations::Germany,
35-
const char * participant = lanelet::Participants::Vehicle);
36-
3727
/**
3828
* @brief get the left adjacent and same_direction lanelet on the routing graph if exists regardless
3929
* of lane change permission

0 commit comments

Comments
 (0)