AWViz-ROS
Loading...
Searching...
No Matches
conversion.hpp
Go to the documentation of this file.
1// Copyright 2024 Kotaro Uetake.
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 AWVIZ_PLUGIN__AUTOWARE_MAP__CONVERSION_HPP_
16#define AWVIZ_PLUGIN__AUTOWARE_MAP__CONVERSION_HPP_
17
18#include <rerun.hpp>
19
20#include <lanelet2_core/LaneletMap.h>
21
22#include <set>
23#include <string>
24#include <vector>
25
26namespace awviz_plugin
27{
32{
33public:
34 LaneletLineStrips() = default;
35
41 void emplace_back(const std::vector<rerun::Position3D> & points)
42 {
43 line_strips_.emplace_back(rerun::LineStrip3D(points));
44 }
45
51 rerun::LineStrips3D as_linestrips() const { return rerun::LineStrips3D(line_strips_); }
52
58 const std::vector<rerun::LineStrip3D> & line_strips() const { return line_strips_; }
59
60private:
61 std::vector<rerun::LineStrip3D> line_strips_;
62};
63
71bool has_attribute(
72 const lanelet::ConstLineString3d & linestring, const std::set<std::string> & attributes);
73
81LaneletLineStrips convert_road_lanelets(
82 const lanelet::LaneletLayer & layer, const lanelet::ConstLanelets & lanelets);
83
90LaneletLineStrips convert_road_boundaries(const lanelet::ConstLanelets & lanelets);
91
98LaneletLineStrips convert_centerlines(const lanelet::ConstLanelets & lanelets);
99
106LaneletLineStrips convert_stop_lines(const lanelet::LineStringLayer & layer);
107
114std::vector<LaneletLineStrips> convert_crosswalks(const lanelet::ConstLanelets & lanelets);
115} // namespace awviz_plugin
116
117#endif // AWVIZ_PLUGIN__AUTOWARE_MAP__CONVERTION_HPP_
A class stores a set of line strips, and creates a new rerun::LineStrips3D object.
Definition: conversion.hpp:32
const std::vector< rerun::LineStrip3D > & line_strips() const
Access the underlying line strip list.
Definition: conversion.hpp:58
void emplace_back(const std::vector< rerun::Position3D > &points)
Append a new line strip to the end of the container.
Definition: conversion.hpp:41
rerun::LineStrips3D as_linestrips() const
Create a rerun::LineStrips3D object.
Definition: conversion.hpp:51
Definition: conversion.hpp:27
LaneletLineStrips convert_road_boundaries(const lanelet::ConstLanelets &lanelets)
Convert road boundaries to line strips.
Definition: conversion.cpp:87
LaneletLineStrips convert_centerlines(const lanelet::ConstLanelets &lanelets)
Convert centerlines to line strips.
Definition: conversion.cpp:124
LaneletLineStrips convert_stop_lines(const lanelet::LineStringLayer &layer)
Convert stop lines to line strips.
Definition: conversion.cpp:147
std::vector< LaneletLineStrips > convert_crosswalks(const lanelet::ConstLanelets &lanelets)
Convert crosswalks to line strips.
Definition: conversion.cpp:169
bool has_attribute(const lanelet::ConstLineString3d &linestring, const std::set< std::string > &attributes)
Check if the input linestring has same attribute in the specified set of attributes.
Definition: conversion.cpp:21
LaneletLineStrips convert_road_lanelets(const lanelet::LaneletLayer &layer, const lanelet::ConstLanelets &lanelets)
Convert road lanelets to line strips.
Definition: conversion.cpp:32