2 #include <boost/noncopyable.hpp> 13 template <
typename Po
intT>
40 using Reverse = std::reverse_iterator<BaseIter>;
48 return inverted ?
RFIter(
Reverse(BaseIter::end(ls_))) : RFIter(BaseIter::begin(ls_));
51 return inverted ?
RFIter(
Reverse(BaseIter::begin(ls_))) : RFIter(BaseIter::end(ls_));
68 template <
typename Po
intT>
92 : data_{std::make_shared<CompoundLineStringData>(ls)} {}
95 template <
typename OtherT,
typename = IfLS<OtherT,
void>>
97 : data_{std::make_shared<CompoundLineStringData>(
102 : data_(
std::move(data)), inverted_{inverted} {}
105 template <
typename OtherT>
107 : data_(other.constData()), inverted_{other.
inverted()} {}
122 bool inverted() const noexcept {
return inverted_; }
137 bool empty() const noexcept {
return size() == 0; }
184 assert(idx < size());
185 return *std::next(begin(), idx);
196 assert(idx < size());
197 const auto first = std::next(begin(), idx);
198 const auto second = idx + 1 == size() ? begin() : std::next(first);
203 size_t numSegments() const noexcept {
return std::max(
size_t(1), size()) - 1; }
233 std::shared_ptr<const CompoundLineStringData>
constData() const noexcept {
return data_; }
238 : data_->lineStrings();
246 auto ids =
utils::transform(data_->lineStrings(), [](
const auto& ls) {
return ls.id(); });
255 bool inverted_{
false};
354 template <
typename Po
intT>
356 return std::any_of(ls.
begin(), ls.
end(), [&
id](
const auto& elem) {
return elem.id() ==
id; });
360 template <
typename Po
int1T,
typename Po
int2T>
365 template <
typename Po
int1T,
typename Po
int2T>
367 return !(rhs == lhs);
369 template <
typename Po
int1T,
typename Po
int2T>
371 return lhs.
size() == rhs.size() && std::equal(lhs.
begin(), lhs.
end(), rhs.begin());
374 template <
typename Po
int1T,
typename Po
int2T>
379 template <
typename Po
int1T,
typename Po
int2T>
381 return !(lhs == rhs);
384 template <
typename Po
int1T,
typename Po
int2T>
386 return !(lhs == rhs);
389 template <
typename Po
intT>
390 inline std::ostream& operator<<(std::ostream& stream, const CompoundLineStringImpl<PointT>& obj) {
391 auto ids = obj.ids();
395 std::copy(ids.begin(), ids.end(), std::ostream_iterator<Id>(stream,
" "));
397 if (obj.inverted()) {
398 stream <<
", inverted";
400 return stream <<
"]";
std::vector< CompoundLineString2d > CompoundLineStrings2d
CompoundLineStringData(ConstLineStrings3d lineStrings)
CompoundHybridLineString2d(const CompoundHybridLineStrings2d &other)
traits::ConstPointT< ConstPoint2d > ConstPointType
internal::SelectCompoundLsIteratorT< ConstPoint3d > RFIter
const ConstLineStrings3d & lineStrings() const
std::vector< ConstLineString3d > ConstLineStrings3d
std::shared_ptr< const CompoundLineStringData > CompoundLineStringDataConstPtr
typename PointTraits< PointT >::BasicPoint BasicPointT
CompoundLineStringImpl(const ConstLineStrings3d &ls=ConstLineStrings3d())
Construct from a vector of ConstLineString3d.
A Compound linestring in 3d (returns Point3d)
typename SelectCompoundLsIterator< T >::Iterator SelectCompoundLsIteratorT
internal::SelectBasicLineStringT< BasicPointType > BasicLineString
RFIter pointsBegin(bool inverted) const
BasicLineString basicLineString() const
create a basic linestring from this linestring
traits::BasicPointT< ConstPoint2d > BasicPointType
CompoundHybridLineString2d invert() const noexcept
create a new, inverted linestring from this one
ConstPrimitiveType< PrimitiveT > toConst(const PrimitiveT &primitive)
Converts a primitive to its matching const type.
const_iterator end() const noexcept
returns an iterator to end of the points
typename internal::SelectCompoundLsIterator< ConstPoint3d >::BaseIterator BaseIter
auto transform(Iterator begin, Iterator end, const Func f)
std::pair< PointT, PointT > Segment
ConstPoints3d points() const
typename PointTraits< PointT >::ConstPoint ConstPointT
VectorT concatenate(ContainerT &&c)
bool operator==(const Attribute &lhs, const Attribute &rhs)
A hybrid compound linestring in 2d (returns BasicPoint2d)
size_t numSegments() const noexcept
Returns the number of (geometrically valid) segments.
std::vector< CompoundLineString3d > CompoundLineStrings3d
CompoundLineStringDataConstPtr data_
CompoundHybridLineString3d invert() const noexcept
create a new, inverted linestring from this one
Ids ids() const
returns the ids of all linestrings in order
Identifies bounding boxes.
internal::SelectCompoundLsIteratorT< ConstPointType > const_iterator
BasicIterator basicBegin() const
returns a normal iterator to the internal point type at begin
CompoundHybridLineString3d(const CompoundHybridLineStrings3d &other)
CompoundLineString3d invert() const noexcept
create a new, inverted linestring from this one
std::shared_ptr< const CompoundLineStringData > constData() const noexcept
returns the internal data on the linestrings managed by this object
const_iterator begin() const noexcept
returns an iterator to the start of the points
CompoundLineString2d(const CompoundLineStrings2d &other)
bool inverted() const noexcept
returns whether this is an inverted CompoundLineString
CompoundLineStringImpl(const CompoundLineStringImpl< OtherT > &other)
construct from other CompoundLineString
RFIter pointsEnd(bool inverted) const
std::reverse_iterator< BaseIter > Reverse
bool operator!=(const Attribute &lhs, const Attribute &rhs)
bool empty() const noexcept
return whether this contains any points
Common data object for all CompoundLineStrings.
A Compound linestring in 2d (returns Point2d)
This iterator iterates over a container of containers as if it was one single container. Succeeding elements that are equal are ignored.
const PointType & front() const noexcept
returns the first point of the first linestring
bool has(const CompoundLineStringImpl< PointT > &ls, Id id)
returns true if element of a primitive has a matching Id
SegmentType segment(size_t idx) const noexcept
returns the n-th segment. If n equals size() -1, the segment from back() to front() is returned...
Segment< ConstPointType > SegmentType
const ConstLineStrings3d ls_
Optional< double > distance
typename SelectBasicLineString< T >::Type SelectBasicLineStringT
const PointType & operator[](size_t idx) const
returns the point at this position
CompoundLineStringImpl(CompoundLineStringDataConstPtr data, bool inverted)
Internal construction from data pointer.
ConstLineStrings3d lineStrings() const
A hybrid compound linestring in 3d (returns BasicPoint3d)
BasicIterator basicEnd() const
returns a normal iterator for the internal point type at end
CompoundLineStringData::RFIter RFIter
const PointType & back() const noexcept
returns the last point of the last linestring
CompoundLineString3d(const CompoundLineStrings3d &other)
A collection of lineStrings that act as one line string.
CompoundLineStringImpl(const std::vector< OtherT > &lss)
Construct from a vector of LineStrings or CompoundLineStrings.
BoundingBox3d to3D(const BoundingBox2d &primitive)
Container invert(const Container &cont)
CompoundLineString2d invert() const noexcept
create a new, inverted linestring from this one
size_t size() const noexcept
return the total number of unique points
std::vector< ConstPoint3d > ConstPoints3d
This class selects which iterator CompoundLineStringImpl needs.
Specialization of traits for points.
std::vector< CompoundHybridLineString3d > CompoundHybridLineStrings3d
std::vector< CompoundHybridLineString2d > CompoundHybridLineStrings2d