Go to the documentation of this file.
6 #include <boost/filesystem.hpp>
9 namespace fs = boost::filesystem;
18 std::equal(rhs.
begin(
false), rhs.
end(
false), lhs.
begin(
false),
19 [](
auto&
p1,
auto&
p2) { return *p1.constData() == *p2.constData(); });
30 std::equal(rhsRegelem.begin(), rhsRegelem.end(), lhsRegelem.begin(),
31 [](
auto& r1,
auto& r2) { return *r1->constData() == *r2->constData(); });
40 std::equal(rhsOuter.begin(), rhsOuter.end(), lhsOuter.begin(),
41 [](
auto& ls1,
auto& ls2) { return *ls1.constData() == *ls2.constData(); }) &&
43 std::equal(rhsRegelem.begin(), rhsRegelem.end(), lhsRegelem.begin(),
44 [](
auto& r1,
auto& r2) { return *r1->constData() == *r2->constData(); });
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();
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();
68 namespace test_setup {
69 inline Id getId(
int& num) {
return -(num++); }
96 inline bool hasId(
const Ids& ids,
Id id) {
return std::find(ids.begin(), ids.end(),
id) != ids.end(); }
120 return Area(
getId(num), {lsO1, lsO2}, {{lsI11, lsI12}, {lsI21, lsI22, lsI23}},
127 char dir[] = {
"/tmp/lanelet2_io_test.XXXXXX"};
128 auto* res = mkdtemp(dir);
129 if (res ==
nullptr) {
LaneletLayer laneletLayer
LineStringLayer lineStringLayer
static constexpr const char StopLine[]
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
const fs::path & get() const
bool operator==(const Attribute &lhs, const Attribute &rhs)
PolygonLayer polygonLayer
Tempfile(std::string name)
static constexpr const char Type[]
RegulatoryElementLayer regulatoryElementLayer
static constexpr const char Parking[]
static constexpr const char Refers[]
static constexpr const char TrafficLight[]
IteratorT begin(bool inverted) const noexcept
const std::shared_ptr< const LineStringData > & constData() const
Lanelet setUpLanelet(int &num, const std::string &type=AttributeValueString::Road)
const LineStrings3d & outerBound()
const LineString3d & rightBound()
static constexpr const char Subtype[]
RegulatoryElementPtrs & regulatoryElements()
const InnerBounds & innerBounds()
static constexpr char RuleName[]
RegulatoryElementPtr setUpGenericRegulatoryElement(int &num)
static constexpr const char Curbstone[]
Area setUpArea(int &num, const std::string &type=AttributeValueString::Parking)
Point3d setUpPoint(int &num, int xOffset=0, const std::string &type=AttributeValueString::Start)
bool hasId(const Ids &ids, Id id)
Tempfile & operator=(Tempfile &&rhs) noexcept=delete
static constexpr const char Road[]
static constexpr const char Start[]
static constexpr char RuleName[]
RuleParameterMap parameters
auto size() const noexcept
static constexpr const char RefLine[]
IteratorT end(bool inverted) const noexcept
RegulatoryElementPtr setUpRegulatoryElement(int &num)
static RegulatoryElementPtr create(const std::string &ruleName, Id id, const RuleParameterMap &map, const AttributeMap &attributes=AttributeMap())
const LineString3d & leftBound()
RegulatoryElementPtrs & regulatoryElements()
LineString3d setUpLineString(int &num, const std::string &type=AttributeValueString::Curbstone)
lanelet2_io
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:03