TestSetup.h
Go to the documentation of this file.
1 #pragma once
5 
6 #include <boost/filesystem.hpp>
7 #include <fstream>
8 
9 namespace fs = boost::filesystem;
10 
11 namespace lanelet {
12 inline bool operator==(const PointData& lhs, const PointData& rhs) {
13  return lhs.id == rhs.id && lhs.attributes == rhs.attributes && lhs.point == rhs.point;
14 }
15 
16 inline bool operator==(const LineStringData& lhs, const LineStringData& rhs) {
17  return rhs.id == lhs.id && rhs.attributes == lhs.attributes && rhs.size() == lhs.size() &&
18  std::equal(rhs.begin(false), rhs.end(false), lhs.begin(false),
19  [](auto& p1, auto& p2) { return *p1.constData() == *p2.constData(); });
20 }
21 inline bool operator==(const RegulatoryElementData& rhs, const RegulatoryElementData& lhs) {
22  return rhs.id == lhs.id && lhs.attributes == rhs.attributes && rhs.parameters.size() == rhs.parameters.size();
23 }
24 inline bool operator==(const LaneletData& lhs, const LaneletData& rhs) {
25  auto rhsRegelem = rhs.regulatoryElements();
26  auto lhsRegelem = lhs.regulatoryElements();
27  return rhs.id == lhs.id && rhs.attributes == lhs.attributes &&
28  *lhs.leftBound().constData() == *rhs.leftBound().constData() &&
29  *lhs.rightBound().constData() == *rhs.rightBound().constData() && lhsRegelem.size() == lhsRegelem.size() &&
30  std::equal(rhsRegelem.begin(), rhsRegelem.end(), lhsRegelem.begin(),
31  [](auto& r1, auto& r2) { return *r1->constData() == *r2->constData(); });
32 }
33 
34 inline bool operator==(const AreaData& lhs, const AreaData& rhs) {
35  auto rhsRegelem = rhs.regulatoryElements();
36  auto lhsRegelem = lhs.regulatoryElements();
37  auto rhsOuter = rhs.outerBound();
38  auto lhsOuter = lhs.outerBound();
39  return rhs.id == lhs.id && rhs.attributes == lhs.attributes && rhsOuter.size() == rhsOuter.size() &&
40  std::equal(rhsOuter.begin(), rhsOuter.end(), lhsOuter.begin(),
41  [](auto& ls1, auto& ls2) { return *ls1.constData() == *ls2.constData(); }) &&
42  lhs.innerBounds().size() == rhs.innerBounds().size() && lhsRegelem.size() == lhsRegelem.size() &&
43  std::equal(rhsRegelem.begin(), rhsRegelem.end(), lhsRegelem.begin(),
44  [](auto& r1, auto& r2) { return *r1->constData() == *r2->constData(); });
45 }
46 
47 template <typename T>
48 inline bool operator==(const PrimitiveLayer<T>& rhs, const PrimitiveLayer<T>& lhs) {
49  return rhs.size() == lhs.size() && std::all_of(rhs.begin(), rhs.end(), [&lhs](auto& v1) {
50  return *v1.constData() == *lhs.find(v1.id())->constData();
51  });
52 }
53 
54 template <>
57  return rhs.size() == lhs.size() && std::all_of(rhs.begin(), rhs.end(), [&lhs](auto& v1) {
58  return *v1->constData() == *(*lhs.find(v1->id()))->constData();
59  });
60 }
61 
62 inline bool operator==(const LaneletMap& rhs, const LaneletMap& lhs) {
63  return lhs.pointLayer == rhs.pointLayer && lhs.lineStringLayer == rhs.lineStringLayer &&
65  lhs.areaLayer == rhs.areaLayer && lhs.laneletLayer == rhs.laneletLayer;
66 }
67 
68 namespace test_setup {
69 inline Id getId(int& num) { return -(num++); }
70 
71 inline Point3d setUpPoint(int& num, int xOffset = 0, const std::string& type = AttributeValueString::Start) {
72  return Point3d(getId(num), xOffset, num, 1, AttributeMap{{AttributeNamesString::Type, type}});
73 }
74 
75 inline LineString3d setUpLineString(int& num, const std::string& type = AttributeValueString::Curbstone) {
76  return LineString3d(getId(num), {setUpPoint(num, 0), setUpPoint(num, 1)},
78 }
79 
84 }
85 
88 }
89 
90 inline Lanelet setUpLanelet(int& num, const std::string& type = AttributeValueString::Road) {
91  auto regelem = setUpRegulatoryElement(num);
92  return Lanelet(getId(num), setUpLineString(num), setUpLineString(num),
93  AttributeMap{{AttributeNamesString::Subtype, type}}, {regelem});
94 }
95 
96 inline bool hasId(const Ids& ids, Id id) { return std::find(ids.begin(), ids.end(), id) != ids.end(); }
97 
98 inline Area setUpArea(int& num, const std::string& type = AttributeValueString::Parking) {
99  Point3d o1(getId(num), 0, 0, 0);
100  Point3d o2(getId(num), 0, 5, 0);
101  Point3d o3(getId(num), 5, 5, 0);
102  Point3d o4(getId(num), 5, 0, 0);
103 
104  Point3d i11(getId(num), 1, 1, 0);
105  Point3d i12(getId(num), 1, 2, 0);
106  Point3d i13(getId(num), 2, 2, 0);
107  Point3d i14(getId(num), 2, 1, 0);
108  Point3d i21(getId(num), 3, 3, 0);
109  Point3d i22(getId(num), 3, 4, 0);
110  Point3d i23(getId(num), 4, 4, 0);
111 
112  LineString3d lsO1(getId(num), {o1, o2, o3});
113  LineString3d lsO2(getId(num), {o1, o4, o3});
114  LineString3d lsI11(getId(num), {i11, i12, i13});
115  LineString3d lsI12(getId(num), {i11, i14, i13});
116  LineString3d lsI21(getId(num), {i22, i21});
117  LineString3d lsI22(getId(num), {i21, i23});
118  LineString3d lsI23(getId(num), {i22, i23});
119  auto regelem = setUpRegulatoryElement(num);
120  return Area(getId(num), {lsO1, lsO2}, {{lsI11, lsI12}, {lsI21, lsI22, lsI23}},
121  AttributeMap{{AttributeNamesString::Subtype, type}}, {regelem});
122 }
123 
124 class Tempfile {
125  public:
126  explicit Tempfile(std::string name) {
127  char dir[] = {"/tmp/lanelet2_io_test.XXXXXX"};
128  auto* res = mkdtemp(dir);
129  if (res == nullptr) {
130  throw lanelet::LaneletError("Failed to crate temporary directory");
131  }
132  dir_ = dir;
133  path_ = fs::path(dir_) / name;
134  }
135  Tempfile(Tempfile&& rhs) noexcept = delete;
136  Tempfile& operator=(Tempfile&& rhs) noexcept = delete;
137  Tempfile(const Tempfile& rhs) = delete;
138  Tempfile& operator=(const Tempfile& rhs) = delete;
139  ~Tempfile() { fs::remove_all(path_); }
140 
141  const fs::path& get() const { return path_; }
142  void touch() { std::ofstream(path_.string()); }
143 
144  private:
145  std::string dir_;
146  fs::path path_;
147 };
148 } // namespace test_setup
149 } // namespace lanelet
lanelet::LaneletMapLayers::laneletLayer
LaneletLayer laneletLayer
lanelet::PrimitiveLayer::begin
iterator begin()
lanelet::LaneletMapLayers::lineStringLayer
LineStringLayer lineStringLayer
lanelet::test_setup::Tempfile
Definition: TestSetup.h:124
lanelet::RegulatoryElementData
lanelet::LaneletData
lanelet::AttributeValueString::StopLine
static constexpr const char StopLine[]
LaneletMap.h
lanelet::LaneletMapLayers::areaLayer
AreaLayer areaLayer
lanelet
lanelet::RegulatoryElementPtr
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
p2
BasicPoint p2
lanelet::LaneletMapLayers::pointLayer
PointLayer pointLayer
lanelet::test_setup::Tempfile::get
const fs::path & get() const
Definition: TestSetup.h:141
lanelet::operator==
bool operator==(const Attribute &lhs, const Attribute &rhs)
lanelet::LaneletMapLayers::polygonLayer
PolygonLayer polygonLayer
lanelet::Id
int64_t Id
lanelet::Ids
std::vector< Id > Ids
lanelet::test_setup::Tempfile::touch
void touch()
Definition: TestSetup.h:142
lanelet::test_setup::Tempfile::Tempfile
Tempfile(std::string name)
Definition: TestSetup.h:126
lanelet::AttributeNamesString::Type
static constexpr const char Type[]
lanelet::LaneletMapLayers::regulatoryElementLayer
RegulatoryElementLayer regulatoryElementLayer
lanelet::AttributeValueString::Parking
static constexpr const char Parking[]
lanelet::RoleNameString::Refers
static constexpr const char Refers[]
BasicRegulatoryElements.h
lanelet::AttributeValueString::TrafficLight
static constexpr const char TrafficLight[]
lanelet::Area
lanelet::LineStringData::begin
IteratorT begin(bool inverted) const noexcept
ConstPrimitive< LineStringData >::constData
const std::shared_ptr< const LineStringData > & constData() const
lanelet::test_setup::setUpLanelet
Lanelet setUpLanelet(int &num, const std::string &type=AttributeValueString::Road)
Definition: TestSetup.h:90
lanelet::test_setup::Tempfile::dir_
std::string dir_
Definition: TestSetup.h:145
lanelet::LaneletMap
lanelet::LineStringData
lanelet::Lanelet
lanelet::AreaData::outerBound
const LineStrings3d & outerBound()
lanelet::LaneletData::rightBound
const LineString3d & rightBound()
lanelet::AttributeNamesString::Subtype
static constexpr const char Subtype[]
lanelet::PrimitiveData::attributes
AttributeMap attributes
lanelet::AreaData::regulatoryElements
RegulatoryElementPtrs & regulatoryElements()
lanelet::PrimitiveLayer
lanelet::PointData::point
BasicPoint3d point
p1
BasicPoint p1
lanelet::AreaData::innerBounds
const InnerBounds & innerBounds()
lanelet::test_setup::Tempfile::path_
fs::path path_
Definition: TestSetup.h:146
lanelet::TrafficLight::RuleName
static constexpr char RuleName[]
lanelet::test_setup::setUpGenericRegulatoryElement
RegulatoryElementPtr setUpGenericRegulatoryElement(int &num)
Definition: TestSetup.h:86
lanelet::AreaData
lanelet::AttributeValueString::Curbstone
static constexpr const char Curbstone[]
lanelet::test_setup::setUpArea
Area setUpArea(int &num, const std::string &type=AttributeValueString::Parking)
Definition: TestSetup.h:98
lanelet::Point3d
lanelet::test_setup::setUpPoint
Point3d setUpPoint(int &num, int xOffset=0, const std::string &type=AttributeValueString::Start)
Definition: TestSetup.h:71
lanelet::test_setup::hasId
bool hasId(const Ids &ids, Id id)
Definition: TestSetup.h:96
lanelet::test_setup::Tempfile::operator=
Tempfile & operator=(Tempfile &&rhs) noexcept=delete
lanelet::AttributeValueString::Road
static constexpr const char Road[]
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
lanelet::PrimitiveLayer::size
size_t size() const
lanelet::AttributeValueString::Start
static constexpr const char Start[]
lanelet::PointData
lanelet::GenericRegulatoryElement::RuleName
static constexpr char RuleName[]
lanelet::LaneletError
lanelet::RegulatoryElementData::parameters
RuleParameterMap parameters
lanelet::LineStringData::size
auto size() const noexcept
lanelet::RoleNameString::RefLine
static constexpr const char RefLine[]
lanelet::LineStringData::end
IteratorT end(bool inverted) const noexcept
lanelet::test_setup::Tempfile::~Tempfile
~Tempfile()
Definition: TestSetup.h:139
lanelet::test_setup::setUpRegulatoryElement
RegulatoryElementPtr setUpRegulatoryElement(int &num)
Definition: TestSetup.h:80
lanelet::PrimitiveData::id
Id id
lanelet::RegulatoryElementFactory::create
static RegulatoryElementPtr create(const std::string &ruleName, Id id, const RuleParameterMap &map, const AttributeMap &attributes=AttributeMap())
lanelet::LaneletData::leftBound
const LineString3d & leftBound()
lanelet::LineString3d
lanelet::test_setup::getId
Id getId(int &num)
Definition: TestSetup.h:69
Exceptions.h
HybridMap< RuleParameters, decltype(RoleNameString::Map)&, RoleNameString::Map >::size
size_t size() const
lanelet::PrimitiveLayer::end
iterator end()
lanelet::LaneletData::regulatoryElements
RegulatoryElementPtrs & regulatoryElements()
lanelet::test_setup::setUpLineString
LineString3d setUpLineString(int &num, const std::string &type=AttributeValueString::Curbstone)
Definition: TestSetup.h:75


lanelet2_io
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:03