Skip to content

Commit

Permalink
Oscar 1181 (#1)
Browse files Browse the repository at this point in the history
Versioning for Lanelet2 primitives:
* Optional parameter "version" in primitives' constructors. Default value 0.   
* Read primitives' versions from file.
* Write primitives' versions into file.
* Possibility to increment version for single primitive.
* Possibility to increment versions for all primitives in layer.
* Possibility to increment all primitives' versions on writing to file by bool parameter (minimum version will be written "1").
* Possibility to set version for single primitive.
* Possibility to set version for all primitives in layer.
* Updated Python API with versioning functionality.
---------

Co-authored-by: Anna Slastnikova <[email protected]>
  • Loading branch information
aslastnikova and AnnaSlastnikova authored Nov 10, 2023
1 parent 33e797a commit e4aa69a
Show file tree
Hide file tree
Showing 20 changed files with 182 additions and 82 deletions.
14 changes: 14 additions & 0 deletions lanelet2_core/include/lanelet2_core/LaneletMap.h
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,17 @@ class PrimitiveLayer {
*/
size_t size() const { return elements_.size(); }

/**
* @brief increments versions for all elements in this layer
*/
void incrementVersions();

/**
* @brief sets target version to all elements in this layer
* @param version target version
*/
void setVersions(uint32_t version);

using ConstSearchFunction = std::function<bool(const internal::SearchBoxT<T>& box, const ConstPrimitiveT& prim)>;
using SearchFunction = std::function<bool(const internal::SearchBoxT<T>& box, const PrimitiveT& prim)>;

Expand Down Expand Up @@ -541,6 +552,9 @@ void registerId(Id id);
template <typename PrimitiveT>
std::vector<ConstLayerPrimitive<PrimitiveT>> findUsages(const PrimitiveLayer<PrimitiveT>& layer, Id id);

template <typename PrimitiveT>
void incrementVersions(const PrimitiveLayer<PrimitiveT>& layer);

ConstLanelets findUsagesInLanelets(const LaneletMapLayers& map, const ConstPoint3d& p);
ConstAreas findUsagesInAreas(const LaneletMapLayers& map, const ConstPoint3d& p);

Expand Down
12 changes: 6 additions & 6 deletions lanelet2_core/include/lanelet2_core/primitives/Lanelet.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@ class LaneletData : public PrimitiveData {
* @see ConstLanelet::ConstLanelet
*/
LaneletData(Id id, LineString3d leftBound, LineString3d rightBound, const AttributeMap& attributes = AttributeMap(),
RegulatoryElementPtrs regulatoryElements = RegulatoryElementPtrs())
: PrimitiveData(id, attributes),
RegulatoryElementPtrs regulatoryElements = RegulatoryElementPtrs(), uint32_t version = 0)
: PrimitiveData(id, attributes, version),
leftBound_{std::move(leftBound)},
rightBound_{std::move(rightBound)},
regulatoryElements_{std::move(regulatoryElements)} {}
Expand Down Expand Up @@ -140,11 +140,11 @@ class ConstLanelet : public ConstPrimitive<LaneletData> {
explicit ConstLanelet(Id id = InvalId)
: ConstLanelet(std::make_shared<LaneletData>(id, LineString3d(), LineString3d()), false) {}

//! Constructs a lanelet from id, attributes, regulatoryElements and bounds.
//! Constructs a lanelet from id, version, attributes, regulatoryElements, bounds.
ConstLanelet(Id id, const LineString3d& leftBound, const LineString3d& rightBound,
const AttributeMap& attributes = AttributeMap(),
const RegulatoryElementPtrs& regulatoryElements = RegulatoryElementPtrs())
: ConstPrimitive{std::make_shared<LaneletData>(id, leftBound, rightBound, attributes, regulatoryElements)} {}
const AttributeMap& attributes = AttributeMap(),
const RegulatoryElementPtrs& regulatoryElements = RegulatoryElementPtrs(), uint32_t version = 0)
: ConstPrimitive{std::make_shared<LaneletData>(id, leftBound, rightBound, attributes, regulatoryElements, version)} {}

//! Construct from the data of a different Lanelet
explicit ConstLanelet(const std::shared_ptr<const LaneletData>& data, bool inverted = false)
Expand Down
10 changes: 6 additions & 4 deletions lanelet2_core/include/lanelet2_core/primitives/LineString.h
Original file line number Diff line number Diff line change
Expand Up @@ -139,8 +139,10 @@ struct SelectInsertIterator<typename SelectLsIterator<Point2d>::Iterator> {
class LineStringData : public PrimitiveData {
public:
explicit LineStringData(Id id) : PrimitiveData(id) {}
LineStringData(Id id, Points3d points, AttributeMap attributes)
: PrimitiveData(id, std::move(attributes)), points_(std::move(points)) {}

LineStringData(Id id, Points3d points, AttributeMap attributes, uint32_t version = 0)
: PrimitiveData(id, std::move(attributes), version), points_(std::move(points)) {}

// NOLINTNEXTLINE
using iterator = internal::ReverseAndForwardIterator<Points3d::iterator>;
// NOLINTNEXTLINE
Expand Down Expand Up @@ -241,8 +243,8 @@ class ConstLineStringImpl : public ConstPrimitive<LineStringData> {

//! Constructs a LineString or similar from an Id and a list of points
explicit ConstLineStringImpl(Id id = InvalId, Points3d points = Points3d(),
const AttributeMap& attributes = AttributeMap())
: ConstPrimitive{std::make_shared<LineStringData>(id, std::move(points), attributes)} {}
const AttributeMap& attributes = AttributeMap(), uint32_t version = 0)
: ConstPrimitive{std::make_shared<LineStringData>(id, std::move(points), attributes, version)} {}

//! Constructs a linestring from the data object of another linestring
explicit ConstLineStringImpl(const std::shared_ptr<const LineStringData>& data, bool inverted = false)
Expand Down
17 changes: 9 additions & 8 deletions lanelet2_core/include/lanelet2_core/primitives/Point.h
Original file line number Diff line number Diff line change
Expand Up @@ -102,10 +102,11 @@ struct ArcCoordinates {

//! Common data management class for all Point primitives.
//! @ingroup DataObjects
class PointData : public PrimitiveData { // NOLINT
public:
PointData(Id id, BasicPoint3d point, const AttributeMap& attributes = AttributeMap())
: PrimitiveData(id, attributes), point(point), point2d_{point.x(), point.y()} {}
class PointData : public PrimitiveData { // NOLINT
public:
PointData(Id id, BasicPoint3d point, const AttributeMap& attributes = AttributeMap(), uint32_t version = 0)
: PrimitiveData(id, attributes, version), point(point), point2d_{point.x(), point.y()} {}

PointData(const PointData&) = delete;
PointData& operator=(const LineStringData&) = delete;
PointData(PointData&&) = default;
Expand Down Expand Up @@ -160,18 +161,18 @@ class ConstPoint2d : public ConstPrimitive<PointData> {
using ConstPrimitive::ConstPrimitive;

//! @brief Construct from an id and a point
ConstPoint2d(Id id, const BasicPoint3d& point, const AttributeMap& attributes = AttributeMap())
: ConstPrimitive<PointData>{std::make_shared<PointData>(id, point, attributes)} {} // NOLINT
ConstPoint2d(Id id, const BasicPoint3d& point, const AttributeMap& attributes = AttributeMap(), uint32_t version = 0)
: ConstPrimitive<PointData>{std::make_shared<PointData>(id, point, attributes, version)} {} // NOLINT

//! @brief Construct from an id and coordinates
/**
* The z coordinate is required because this point can be converted to a 3d
* point, where z matters.
*/
explicit ConstPoint2d(Id id = InvalId, double x = 0., double y = 0., double z = 0.,
const AttributeMap& attributes = AttributeMap())
const AttributeMap& attributes = AttributeMap(), uint32_t version = 0)
: ConstPrimitive<PointData>{std::make_shared<PointData>( // NOLINT
id, BasicPoint3d(x, y, z), attributes)} {}
id, BasicPoint3d(x, y, z), attributes, version)} {}

//! A ConstPoint 2d is implicitly convertible to a normal 2d point
operator BasicPoint2d() const noexcept { // NOLINT
Expand Down
8 changes: 7 additions & 1 deletion lanelet2_core/include/lanelet2_core/primitives/Primitive.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,11 @@ class PrimitiveData {
/**
* @brief Constructs a PrimitiveData object
*/
explicit PrimitiveData(Id id, AttributeMap attributes = AttributeMap()) : id{id}, attributes{std::move(attributes)} {}

PrimitiveData(Id id, AttributeMap attributes = AttributeMap(), uint32_t version = 0) : id{id}, attributes{std::move(attributes)}, version{version} {}

Id id{InvalId}; //!< Id of this primitive (unique across one map)
uint32_t version{0}; //!< Version of this primitive
AttributeMap attributes; //!< attributes of this primitive
protected:
~PrimitiveData() = default;
Expand Down Expand Up @@ -95,6 +97,8 @@ class ConstPrimitive {
*/
Id id() const noexcept { return constData_->id; }

uint32_t version() const noexcept { return constData_->version; }

//! check whether this primitive has a specific attribute
bool hasAttribute(const std::string& name) const noexcept { return attributes().find(name) != attributes().end(); }

Expand Down Expand Up @@ -269,6 +273,8 @@ class Primitive : public DerivedConstPrimitive {
*/
void setId(Id id) noexcept { data()->id = id; }

void setVersion(uint32_t version) noexcept { data()->version = version; }

//! @brief set or overwrite an attribute
void setAttribute(const std::string& name, const Attribute& attribute) { attributes()[name] = attribute; }

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -194,6 +194,8 @@ class RegulatoryElement // NOLINT
*/
void setId(Id id) noexcept { data()->id = id; }

void setVersion(uint32_t version) noexcept { data()->version = version; }

//! Returns all parameters as const object (coversion overhead for const)
ConstRuleParameterMap getParameters() const;

Expand Down
40 changes: 40 additions & 0 deletions lanelet2_core/src/LaneletMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -472,6 +472,46 @@ typename PrimitiveLayer<T>::const_iterator PrimitiveLayer<T>::find(Id id) const
return elements_.find(id);
}


/**
* @brief This namespace defines function conditionally returning reference:
* - if an argument is a ptr, returns the reference to the object it points to
* - if an argument is an object, returns the reference to the object
*/
namespace {
template <typename T>
struct is_shared_ptr : std::false_type{};

template <typename T>
struct is_shared_ptr<std::shared_ptr<T>> : std::true_type{};

template <typename T>
auto getReference(T& object) -> std::enable_if_t<is_shared_ptr<T>::value, decltype(*object)> {
return *object;
}

template <typename T>
auto getReference(T& object) -> std::enable_if_t<!is_shared_ptr<T>::value, T&> {
return object;
}
}

template <typename T>
void PrimitiveLayer<T>::incrementVersions() {
for (auto& pair : elements_) {
auto& elem = getReference(pair.second);
elem.setVersion(elem.version() + 1);
}
}

template <typename T>
void PrimitiveLayer<T>::setVersions(uint32_t version) {
for (auto& pair : elements_) {
auto& elem = getReference(pair.second);
elem.setVersion(version);
}
}

template <typename T>
typename PrimitiveLayer<T>::const_iterator PrimitiveLayer<T>::begin() const {
return elements_.begin();
Expand Down
3 changes: 2 additions & 1 deletion lanelet2_examples/src/04_reading_and_writing/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,8 @@ class FakeWriter : public lanelet::io_handlers::Writer {
public:
using Writer::Writer;
void write(const std::string& /*filename*/, const lanelet::LaneletMap& /*laneletMap*/,
lanelet::ErrorMessages& /*errors*/, const lanelet::io::Configuration& /*params*/) const override {
lanelet::ErrorMessages& /*errors*/, const lanelet::io::Configuration& /*params*/,
bool /*increment_versions*/) const override {
// this writer does just nothing
}
static constexpr const char* extension() {
Expand Down
10 changes: 5 additions & 5 deletions lanelet2_io/include/lanelet2_io/Io.h
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ std::vector<std::string> supportedParserExtensions();
* (lat/lon) data. If no origin is specified, the written map will most likely be not correctly located and deformed.
*/
void write(const std::string& filename, const lanelet::LaneletMap& map, const Origin& origin = Origin::defaultOrigin(),
ErrorMessages* errors = nullptr, const io::Configuration& params = io::Configuration());
ErrorMessages* errors = nullptr, const io::Configuration& params = io::Configuration(), bool increment_versions = false);

/**
* @brief writes a map to a file
Expand All @@ -125,7 +125,7 @@ void write(const std::string& filename, const lanelet::LaneletMap& map, const Or
* @throws lanelet2::IOError if the file could not be created or writing failed.
*/
void write(const std::string& filename, const LaneletMap& map, const Projector& projector,
ErrorMessages* errors = nullptr, const io::Configuration& params = io::Configuration());
ErrorMessages* errors = nullptr, const io::Configuration& params = io::Configuration(), bool increment_versions = false);

/**
* @brief writes a map to a file
Expand All @@ -140,8 +140,8 @@ void write(const std::string& filename, const LaneletMap& map, const Projector&
*/
void write(const std::string& filename, const lanelet::LaneletMap& map, const std::string& writerName,
const Origin& origin = Origin::defaultOrigin(), ErrorMessages* errors = nullptr,
const io::Configuration& params = io::Configuration());

const io::Configuration& params = io::Configuration(), bool increment_versions = false);
/**
* @brief writes a map to a file
* @param filename file to write to (parent folders must exist!). The extension is used to deduce the format.
Expand All @@ -155,7 +155,7 @@ void write(const std::string& filename, const lanelet::LaneletMap& map, const st
*/
void write(const std::string& filename, const LaneletMap& map, const std::string& writerName,
const Projector& projector, ErrorMessages* errors = nullptr,
const io::Configuration& params = io::Configuration());
const io::Configuration& params = io::Configuration(), bool increment_versions = false);

/**
* @brief returns the names of the currently registered writing (writers from plugins included)
Expand Down
2 changes: 1 addition & 1 deletion lanelet2_io/include/lanelet2_io/io_handlers/BinHandler.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ class BinWriter : public Writer {
using Writer::Writer;

void write(const std::string& filename, const LaneletMap& laneletMap, ErrorMessages& /*errors*/,
const io::Configuration& /*params*/) const override;
const io::Configuration& /*params*/, bool /*increment_versions*/ = false) const override;

static constexpr const char* extension() { return ".bin"; }

Expand Down
13 changes: 7 additions & 6 deletions lanelet2_io/include/lanelet2_io/io_handlers/OsmFile.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,35 +27,36 @@ struct Primitive {
Primitive(const Primitive& rhs) = delete;
Primitive& operator=(const Primitive& rhs) = delete;
virtual ~Primitive() = default;
Primitive(Id id, Attributes attributes) : id{id}, attributes{std::move(attributes)} {}
Primitive(Id id, Attributes attributes, uint32_t version = 0) : id{id}, attributes{std::move(attributes)}, version{version} {}
virtual std::string type() = 0;

Id id{0};
Attributes attributes;
uint32_t version{0};
};

//! Osm node object
struct Node : public Primitive {
Node() = default;
Node(Id id, Attributes attributes, GPSPoint point) : Primitive{id, std::move(attributes)}, point{point} {}
Node(Id id, Attributes attributes, GPSPoint point, uint32_t version = 0) : Primitive{id, std::move(attributes), version}, point{point} {}
std::string type() override { return "node"; }
GPSPoint point;
};

//! Osm way object
struct Way : public Primitive {
Way() = default;
Way(Id id, Attributes attributes, std::vector<Node*> nodes)
: Primitive{id, std::move(attributes)}, nodes{std::move(nodes)} {}
Way(Id id, Attributes attributes, std::vector<Node*> nodes, uint32_t version = 0)
: Primitive{id, std::move(attributes), version}, nodes{std::move(nodes)} {}
std::string type() override { return "way"; }
std::vector<Node*> nodes;
};

//! Osm relation object
struct Relation : public Primitive {
Relation() = default;
Relation(Id id, Attributes attributes, Roles roles = Roles())
: Primitive{id, std::move(attributes)}, members{std::move(roles)} {}
Relation(Id id, Attributes attributes, Roles roles = Roles(), uint32_t version = 0)
: Primitive{id, std::move(attributes), version}, members{std::move(roles)} {}
std::string type() override { return "relation"; }
Roles members;
};
Expand Down
7 changes: 4 additions & 3 deletions lanelet2_io/include/lanelet2_io/io_handlers/OsmHandler.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,11 @@ class OsmWriter : public Writer {
* "josm_format_elevation": whether to format elevation to 2 decimal places as required by JSOM, "false" by default
*/
void write(const std::string& filename, const LaneletMap& laneletMap, ErrorMessages& errors,
const io::Configuration& params = io::Configuration()) const override;

const io::Configuration& params = io::Configuration(), bool increment_versions = false) const override;
std::unique_ptr<osm::File> toOsmFile(const LaneletMap& laneletMap, ErrorMessages& errors,
const io::Configuration& params = io::Configuration()) const;
const io::Configuration& params = io::Configuration(),
bool increment_versions = false) const;

static constexpr const char* extension() { return ".osm"; }

Expand Down
2 changes: 1 addition & 1 deletion lanelet2_io/include/lanelet2_io/io_handlers/Writer.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class Writer : public IOHandler {
using Ptr = std::shared_ptr<Writer>;

virtual void write(const std::string& filename, const LaneletMap& laneletMap, ErrorMessages& errors,
const io::Configuration& params = io::Configuration()) const = 0;
const io::Configuration& params = io::Configuration(), bool increment_versions = false) const = 0;

// IOHandler interface
private:
Expand Down
2 changes: 1 addition & 1 deletion lanelet2_io/src/BinHandler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ RegisterWriter<BinWriter> regWriter;

} // namespace

void BinWriter::write(const std::string& filename, const LaneletMap& laneletMap, ErrorMessages& /*errors*/, const io::Configuration& /*params*/) const {
void BinWriter::write(const std::string& filename, const LaneletMap& laneletMap, ErrorMessages& /*errors*/, const io::Configuration& /*params*/, bool /*increment_versions*/) const {
std::ofstream fs(filename, std::ofstream::binary);
if (!fs.good()) {
throw ParseError("Failed open archive " + filename);
Expand Down
16 changes: 8 additions & 8 deletions lanelet2_io/src/Io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,24 +58,24 @@ std::vector<std::string> supportedParsers() { return io_handlers::ParserFactory:

std::vector<std::string> supportedParserExtensions() { return io_handlers::ParserFactory::availableExtensions(); }

void write(const std::string& filename, const LaneletMap& map, const Origin& origin, ErrorMessages* errors, const io::Configuration& params) {
write(filename, map, defaultProjection(origin), errors, params);
void write(const std::string& filename, const LaneletMap& map, const Origin& origin, ErrorMessages* errors, const io::Configuration& params, bool increment_versions) {
write(filename, map, defaultProjection(origin), errors, params, increment_versions);
}

void write(const std::string& filename, const LaneletMap& map, const Projector& projector, ErrorMessages* errors, const io::Configuration& params) {
void write(const std::string& filename, const LaneletMap& map, const Projector& projector, ErrorMessages* errors, const io::Configuration& params, bool increment_versions) {
ErrorMessages err;
io_handlers::WriterFactory::createFromExtension(extension(filename), projector, params)->write(filename, map, err, params);
io_handlers::WriterFactory::createFromExtension(extension(filename), projector, params)->write(filename, map, err, params, increment_versions);
handleErrorsOrThrow<WriteError>(err, errors);
}

void write(const std::string& filename, const LaneletMap& map, const std::string& writerName, const Origin& origin, ErrorMessages* errors, const io::Configuration& params) {
write(filename, map, writerName, defaultProjection(origin), errors, params);
void write(const std::string& filename, const LaneletMap& map, const std::string& writerName, const Origin& origin, ErrorMessages* errors, const io::Configuration& params, bool increment_versions) {
write(filename, map, writerName, defaultProjection(origin), errors, params, increment_versions);
}

void write(const std::string& filename, const LaneletMap& map, const std::string& writerName,
const Projector& projector, ErrorMessages* errors, const io::Configuration& params) {
const Projector& projector, ErrorMessages* errors, const io::Configuration& params, bool increment_versions) {
ErrorMessages err;
io_handlers::WriterFactory::create(writerName, projector, params)->write(filename, map, err, params);
io_handlers::WriterFactory::create(writerName, projector, params)->write(filename, map, err, params, increment_versions);
handleErrorsOrThrow<WriteError>(err, errors);
}

Expand Down
Loading

0 comments on commit e4aa69a

Please sign in to comment.