19
19
20
20
// NOLINTBEGIN(readability-identifier-naming)
21
21
22
- #include < autoware_auto_mapping_msgs /msg/had_map_bin .hpp>
22
+ #include < autoware_map_msgs /msg/lanelet_map_bin .hpp>
23
23
#include < geometry_msgs/msg/point.hpp>
24
24
#include < geometry_msgs/msg/point32.hpp>
25
25
#include < geometry_msgs/msg/polygon.hpp>
@@ -36,17 +36,17 @@ namespace lanelet::utils::conversion
36
36
* @param map [lanelet map data]
37
37
* @param msg [converted ROS message. Only "data" field is filled]
38
38
*/
39
- void toBinMsg (const lanelet::LaneletMapPtr & map, autoware_auto_mapping_msgs ::msg::HADMapBin * msg);
39
+ void toBinMsg (const lanelet::LaneletMapPtr & map, autoware_map_msgs ::msg::LaneletMapBin * msg);
40
40
41
41
/* *
42
42
* [fromBinMsg converts ROS message into lanelet2 data. Similar implementation
43
43
* to lanelet::io_handlers::BinHandler::parse()]
44
44
* @param msg [ROS message for lanelet map]
45
45
* @param map [Converted lanelet2 data]
46
46
*/
47
- void fromBinMsg (const autoware_auto_mapping_msgs ::msg::HADMapBin & msg, lanelet::LaneletMapPtr map);
47
+ void fromBinMsg (const autoware_map_msgs ::msg::LaneletMapBin & msg, lanelet::LaneletMapPtr map);
48
48
void fromBinMsg (
49
- const autoware_auto_mapping_msgs ::msg::HADMapBin & msg, lanelet::LaneletMapPtr map,
49
+ const autoware_map_msgs ::msg::LaneletMapBin & msg, lanelet::LaneletMapPtr map,
50
50
lanelet::traffic_rules::TrafficRulesPtr * traffic_rules,
51
51
lanelet::routing::RoutingGraphPtr * routing_graph);
52
52
0 commit comments