diff --git a/patch/ros-jazzy-lanelet2-core.win.patch b/patch/ros-jazzy-lanelet2-core.win.patch new file mode 100644 index 00000000..e6938cbb --- /dev/null +++ b/patch/ros-jazzy-lanelet2-core.win.patch @@ -0,0 +1,345 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 37a3107f..a8620438 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -3,6 +3,10 @@ set(MRT_PKG_VERSION 4.0.0) + cmake_minimum_required(VERSION 3.5.1) + project(lanelet2_core) + ++if(WIN32 AND MSVC) ++ set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++endif() ++ + ################### + ## Find packages ## + ################### +diff --git a/include/lanelet2_core/geometry/Area.h b/include/lanelet2_core/geometry/Area.h +index 1e2bdeca..feb1e79a 100644 +--- a/include/lanelet2_core/geometry/Area.h ++++ b/include/lanelet2_core/geometry/Area.h +@@ -12,8 +12,8 @@ namespace geometry { + * @param point point to check + * @return true if the point is within or at the border, false otherwise + */ +-template +-IfAr inside(const AreaT& area, const BasicPoint2d& point); ++template = 0> ++bool inside(const AreaT& area, const BasicPoint2d& point); + + /** + * @brief calculates an up-right 2d bounding box +@@ -22,30 +22,30 @@ IfAr inside(const AreaT& area, const BasicPoint2d& point); + * + * Linear on number of points. + */ +-template +-IfAr boundingBox2d(const AreaT& area); ++template = 0> ++BoundingBox2d boundingBox2d(const AreaT& area); + + /** + * @brief calculates 3d bounding box + * @param area area to calculate it from. + * @return the bounding box + */ +-template +-IfAr boundingBox3d(const AreaT& area); ++template = 0> ++BoundingBox3d boundingBox3d(const AreaT& area); + + //! test whether two areas intersect in 2d. +-template +-IfAr intersects2d(const Area1T& area, const Area2T& otherArea); ++template = 0> ++bool intersects2d(const Area1T& area, const Area2T& otherArea); + + //! test whether two areas overlap in 2d (common area < 0). + //! This is an approximation that ignores the holes of the areas! +-template +-IfAr overlaps2d(const AreaT& area, const AreaT& otherArea); ++template = 0> ++bool overlaps2d(const AreaT& area, const AreaT& otherArea); + + //! test whether two areas overlap in 3d. + //! This is an approximation that uses the overlap of the outer bound +-template +-IfAr overlaps3d(const AreaT& area, const AreaT& otherArea, double heightTolerance); ++template = 0> ++bool overlaps3d(const AreaT& area, const AreaT& otherArea, double heightTolerance); + + //! test whether an area and a lanelet overlap in 2d + //! This is an approximation that uses the overlap of the outer bound +diff --git a/include/lanelet2_core/geometry/Lanelet.h b/include/lanelet2_core/geometry/Lanelet.h +index f046185c..77df47e7 100644 +--- a/include/lanelet2_core/geometry/Lanelet.h ++++ b/include/lanelet2_core/geometry/Lanelet.h +@@ -10,8 +10,8 @@ namespace geometry { + * @param point point to check + * @return true if the point is within or at the border, false otherwise + */ +-template +-IfLL inside(const LaneletT& lanelet, const BasicPoint2d& point); ++template = 0> ++bool inside(const LaneletT& lanelet, const BasicPoint2d& point); + + /** + * @brief approximates length by sampling points along left bound +@@ -68,16 +68,16 @@ double distanceToCenterline3d(const LaneletT& lanelet, const BasicPoint3d& point + * + * Linear on number of points. + */ +-template +-IfLL boundingBox2d(const LaneletT& lanelet); ++template = 0> ++BoundingBox2d boundingBox2d(const LaneletT& lanelet); + + /** + * @brief calculates 3d bounding box + * @param lanelet lanelet to calculate it from. + * @return the bounding box + */ +-template +-IfLL boundingBox3d(const LaneletT& lanelet); ++template = 0> ++BoundingBox3d boundingBox3d(const LaneletT& lanelet); + + /** + * @brief test whether two lanelets intersect in 2d. +@@ -89,8 +89,8 @@ IfLL boundingBox3d(const LaneletT& lanelet); + * This also returns true if the two lanelets only touch each other. Use + * overlaps if you do not want this. + */ +-template +-IfLL intersects2d(const Lanelet1T& lanelet, const Lanelet2T& otherLanelet); ++template = 0> ++bool intersects2d(const Lanelet1T& lanelet, const Lanelet2T& otherLanelet); + + /** + * @brief test whether two lanelets overlap in 2d. +diff --git a/include/lanelet2_core/geometry/Polygon.h b/include/lanelet2_core/geometry/Polygon.h +index 63c9a731..4a77599c 100644 +--- a/include/lanelet2_core/geometry/Polygon.h ++++ b/include/lanelet2_core/geometry/Polygon.h +@@ -245,14 +245,14 @@ IfPoly distanceToBorder3d(const Polygon3dT& poly1, const Pol + * + * @return The enclosing axis aligned bounding box of all points. + */ +-template +-IfPoly boundingBox3d(const Polygon3dT& polygon); ++template = 0> ++BoundingBox3d boundingBox3d(const Polygon3dT& polygon); + +-template +-IfPoly boundingBox2d(const Polygon2dT& polygon); ++template = 0> ++BoundingBox2d boundingBox2d(const Polygon2dT& polygon); + +-template +-IfPoly boundingBox3d(const Polygon3dT& polygon) { ++template > ++BoundingBox3d boundingBox3d(const Polygon3dT& polygon) { + static_assert(traits::is3D(), "Please call this function with a 3D type!"); + BoundingBox3d bb; + for (const auto& p : polygon) { +@@ -261,8 +261,8 @@ IfPoly boundingBox3d(const Polygon3dT& polygon) { + return bb; + } + +-template +-IfPoly boundingBox2d(const Polygon2dT& polygon) { ++template > ++BoundingBox2d boundingBox2d(const Polygon2dT& polygon) { + static_assert(traits::is2D(), "Please call this function with a 2D type!"); + BoundingBox2d bb; + for (const auto& p : polygon) { +diff --git a/include/lanelet2_core/geometry/impl/Area.h b/include/lanelet2_core/geometry/impl/Area.h +index 0edece94..4be56d0b 100644 +--- a/include/lanelet2_core/geometry/impl/Area.h ++++ b/include/lanelet2_core/geometry/impl/Area.h +@@ -16,36 +16,36 @@ struct GetGeometry> { + }; + } // namespace internal + +-template +-IfAr inside(const AreaT& area, const BasicPoint2d& point) { ++template > ++bool inside(const AreaT& area, const BasicPoint2d& point) { + return boost::geometry::covered_by(point, area.basicPolygonWithHoles2d()); + } + +-template +-IfAr boundingBox2d(const AreaT& area) { ++template > ++BoundingBox2d boundingBox2d(const AreaT& area) { + return boundingBox2d(traits::to2D(area.outerBoundPolygon())); + } + +-template +-IfAr boundingBox3d(const AreaT& area) { ++template > ++BoundingBox3d boundingBox3d(const AreaT& area) { + return boundingBox3d(area.outerBoundPolygon()); + } + +-template +-IfAr intersects2d(const Area1T& area, const Area2T& otherArea) { ++template > ++bool intersects2d(const Area1T& area, const Area2T& otherArea) { + if (area == otherArea) { + return true; + } + return intersects(area.basicPolygonWithHoles2d(), otherArea.basicPolygonWithHoles2d()); + } + +-template +-IfAr overlaps2d(const AreaT& area, const AreaT& otherArea) { ++template > ++bool overlaps2d(const AreaT& area, const AreaT& otherArea) { + return overlaps2d(traits::to2D(area.outerBoundPolygon()), traits::to2D(otherArea.outerBoundPolygon())); + } + +-template +-IfAr overlaps3d(const AreaT& area, const AreaT& otherArea, double heightTolerance) { ++template > ++bool overlaps3d(const AreaT& area, const AreaT& otherArea, double heightTolerance) { + return overlaps3d(area.outerBoundPolygon(), otherArea.outerBoundPolygon(), heightTolerance); + } + +diff --git a/include/lanelet2_core/geometry/impl/Lanelet.h b/include/lanelet2_core/geometry/impl/Lanelet.h +index 39a82a04..cdc4b512 100644 +--- a/include/lanelet2_core/geometry/impl/Lanelet.h ++++ b/include/lanelet2_core/geometry/impl/Lanelet.h +@@ -21,8 +21,8 @@ struct GetGeometry> { + }; + } // namespace internal + +-template +-IfLL inside(const LaneletT& lanelet, const BasicPoint2d& point) { ++template > ++bool inside(const LaneletT& lanelet, const BasicPoint2d& point) { + return boost::geometry::covered_by(point, lanelet.polygon2d()); + } + +@@ -36,22 +36,22 @@ double distanceToCenterline3d(const LaneletT& lanelet, const BasicPoint3d& point + return distance(lanelet.centerline3d(), point); + } + +-template +-IfLL boundingBox2d(const LaneletT& lanelet) { ++template > ++BoundingBox2d boundingBox2d(const LaneletT& lanelet) { + BoundingBox2d bb = boundingBox2d(lanelet.leftBound2d()); + bb.extend(boundingBox2d(lanelet.rightBound2d())); + return bb; + } + +-template +-IfLL boundingBox3d(const LaneletT& lanelet) { ++template > ++BoundingBox3d boundingBox3d(const LaneletT& lanelet) { + BoundingBox3d bb = boundingBox3d(lanelet.leftBound3d()); + bb.extend(boundingBox3d(lanelet.rightBound3d())); + return bb; + } + +-template +-IfLL intersects2d(const Lanelet1T& lanelet, const Lanelet2T& otherLanelet) { ++template > ++bool intersects2d(const Lanelet1T& lanelet, const Lanelet2T& otherLanelet) { + if (lanelet.constData() == otherLanelet.constData()) { + return true; + } +diff --git a/include/lanelet2_core/geometry/impl/LineString.h b/include/lanelet2_core/geometry/impl/LineString.h +index a6461cfc..990286b9 100644 +--- a/include/lanelet2_core/geometry/impl/LineString.h ++++ b/include/lanelet2_core/geometry/impl/LineString.h +@@ -799,8 +799,9 @@ IfLS> projectedPoint3d(cons + return internal::projectedPoint3d(traits::toHybrid(l1), traits::toHybrid(l2)); + } + +-template +-IfLS2 distance3d(const LineString3d1T& l1, const LineString3d2T& l2) { ++template = 0> ++double distance3d(const LineString3d1T& l1, const LineString3d2T& l2) { + auto projPoint = internal::projectedPoint3d(traits::toHybrid(traits::to3D(l1)), traits::toHybrid(traits::to3D(l2))); + return (projPoint.first - projPoint.second).norm(); + } +diff --git a/include/lanelet2_core/primitives/Polygon.h b/include/lanelet2_core/primitives/Polygon.h +index a458cb49..6c9dfab6 100644 +--- a/include/lanelet2_core/primitives/Polygon.h ++++ b/include/lanelet2_core/primitives/Polygon.h +@@ -394,8 +394,9 @@ inline BasicPolygon2d to2D(const BasicPolygon3d& primitive) { + return p2d; + } + +-template +-std::enable_if_t(), BasicPolygon2d> toBasicPolygon2d(const PolygonT& t) { ++template (), int> = 0> ++BasicPolygon2d toBasicPolygon2d(const PolygonT& t) { + return traits::to2D(t).basicPolygon(); + } + +@@ -411,8 +412,9 @@ inline BasicPolygon2d toBasicPolygon2d(const BasicPolygon3d& t) + + inline BasicPolygon2d toBasicPolygon2d(BasicPolygon2d&& t) { return std::move(t); } + +-template +-std::enable_if_t(), BasicPolygon3d> toBasicPolygon3d(const PolygonT& t) { ++template (), int> = 0> ++BasicPolygon3d toBasicPolygon3d(const PolygonT& t) { + return traits::to3D(t).basicPolygon(); + } + +diff --git a/include/lanelet2_core/utility/HybridMap.h b/include/lanelet2_core/utility/HybridMap.h +index 9ba57a4e..85c63d0b 100644 +--- a/include/lanelet2_core/utility/HybridMap.h ++++ b/include/lanelet2_core/utility/HybridMap.h +@@ -65,7 +65,7 @@ void replaceIterator(Vector& v, const Iterator& replace, const Iterator& by) { + */ + template + class HybridMap { +- using Array = detail::ArrayView; ++ using Array = lanelet::detail::ArrayView; + + public: + using Map = std::map; +@@ -82,19 +82,19 @@ class HybridMap { + HybridMap() noexcept = default; + HybridMap(HybridMap&& rhs) noexcept : m_(std::move(rhs.m_)), v_{std::move(rhs.v_)} { + // move invalidates no iterators except end +- detail::replaceIterator(v_, rhs.m_.end(), m_.end()); ++ lanelet::detail::replaceIterator(v_, rhs.m_.end(), m_.end()); + } + HybridMap& operator=(HybridMap&& rhs) noexcept { + m_ = std::move(rhs.m_); + v_ = std::move(rhs.v_); + // move invalidates no iterators except end +- detail::replaceIterator(v_, rhs.m_.end(), m_.end()); ++ lanelet::detail::replaceIterator(v_, rhs.m_.end(), m_.end()); + return *this; + } +- HybridMap(const HybridMap& rhs) : m_{rhs.m_}, v_{detail::copyIterators(rhs.v_, rhs.m_, m_)} {} ++ HybridMap(const HybridMap& rhs) : m_{rhs.m_}, v_{lanelet::detail::copyIterators(rhs.v_, rhs.m_, m_)} {} + HybridMap& operator=(const HybridMap& rhs) { + m_ = rhs.m_; +- v_ = detail::copyIterators(rhs.v_, rhs.m_, m_); ++ v_ = lanelet::detail::copyIterators(rhs.v_, rhs.m_, m_); + return *this; + } + HybridMap(const std::initializer_list>& list) { +diff --git a/src/LaneletMap.cpp b/src/LaneletMap.cpp +index ad53b2f2..0d53f953 100644 +--- a/src/LaneletMap.cpp ++++ b/src/LaneletMap.cpp +@@ -312,7 +312,7 @@ struct PrimitiveLayer::Tree { + using TreeNode = std::pair; + using RTree = bgi::rtree>; + static TreeNode treeNode(const Point3d& p) { return {Point2d(p).basicPoint(), p}; } +- explicit Tree(const PrimitiveLayer::Map& primitives) { ++ explicit Tree(const PrimitiveLayer::Map& primitives) { + std::vector nodes; + nodes.reserve(primitives.size()); + std::transform(primitives.begin(), primitives.end(), std::back_inserter(nodes), diff --git a/patch/ros-jazzy-lanelet2-examples.win.patch b/patch/ros-jazzy-lanelet2-examples.win.patch new file mode 100644 index 00000000..b6a5e82a --- /dev/null +++ b/patch/ros-jazzy-lanelet2-examples.win.patch @@ -0,0 +1,41 @@ +diff --git a/src/04_reading_and_writing/main.cpp b/src/04_reading_and_writing/main.cpp +index a1776914..0d39f6ee 100644 +--- a/src/04_reading_and_writing/main.cpp ++++ b/src/04_reading_and_writing/main.cpp +@@ -4,7 +4,12 @@ + #include + #include + ++#ifdef _WIN32 ++#include ++#include ++#else + #include ++#endif + + #pragma GCC diagnostic ignored "-Wunused-but-set-variable" + +@@ -15,12 +20,23 @@ namespace { + std::string exampleMapPath = std::string(PKG_DIR) + "/../lanelet2_maps/res/mapping_example.osm"; + + std::string tempfile(const std::string& name) { ++#ifdef _WIN32 ++ char tmpDir[] = "C:\\tmp\\lanelet2_example_XXXXXX"; ++ if (_mktemp_s(tmpDir, sizeof(tmpDir)) != 0) { ++ throw std::runtime_error("Failed to create a unique temporary directory name"); ++ } ++ if (_mkdir(tmpDir) != 0) { ++ throw std::runtime_error("Failed to create temporary directory"); ++ } ++ return std::string(tmpDir) + '\\' + name; ++#else + char tmpDir[] = "/tmp/lanelet2_example_XXXXXX"; + auto* file = mkdtemp(tmpDir); + if (file == nullptr) { + throw lanelet::IOError("Failed to open a temporary file for writing"); + } + return std::string(file) + '/' + name; ++#endif + } + } // namespace + diff --git a/patch/ros-jazzy-lanelet2-io.win.patch b/patch/ros-jazzy-lanelet2-io.win.patch new file mode 100644 index 00000000..cf2a08af --- /dev/null +++ b/patch/ros-jazzy-lanelet2-io.win.patch @@ -0,0 +1,26 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index e4828bf4..1ea63296 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -3,6 +3,10 @@ set(MRT_PKG_VERSION 4.0.0) + cmake_minimum_required(VERSION 3.5.1) + project(lanelet2_io) + ++if(WIN32 AND MSVC) ++ set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++endif() ++ + ################### + ## Find packages ## + ################### +@@ -52,6 +56,10 @@ mrt_add_library(${PROJECT_NAME} + SOURCES ${PROJECT_SOURCE_FILES_SRC} + ) + ++target_compile_definitions(${PROJECT_NAME} ++ PUBLIC "$<$:_USE_MATH_DEFINES>" ++ ) ++ + ############# + ## Install ## + ############# diff --git a/patch/ros-jazzy-lanelet2-matching.win.patch b/patch/ros-jazzy-lanelet2-matching.win.patch new file mode 100644 index 00000000..3b28113c --- /dev/null +++ b/patch/ros-jazzy-lanelet2-matching.win.patch @@ -0,0 +1,26 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 54c5dcee..ad73dd2f 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -3,6 +3,10 @@ set(MRT_PKG_VERSION 4.0.0) + cmake_minimum_required(VERSION 3.5.1) + project(lanelet2_matching) + ++if(WIN32 AND MSVC) ++ set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++endif() ++ + ################### + ## Find packages ## + ################### +@@ -52,6 +56,10 @@ mrt_add_library(${PROJECT_NAME} + SOURCES ${PROJECT_SOURCE_FILES_SRC} + ) + ++target_compile_definitions(${PROJECT_NAME} ++ PUBLIC "$<$:_USE_MATH_DEFINES>" ++ ) ++ + ############# + ## Install ## + ############# diff --git a/patch/ros-jazzy-lanelet2-projection.win.patch b/patch/ros-jazzy-lanelet2-projection.win.patch new file mode 100644 index 00000000..2e299d0c --- /dev/null +++ b/patch/ros-jazzy-lanelet2-projection.win.patch @@ -0,0 +1,15 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 648ff82a..c3a3393d 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -3,6 +3,10 @@ set(MRT_PKG_VERSION 4.0.0) + cmake_minimum_required(VERSION 3.5.1) + project(lanelet2_projection) + ++if(WIN32 AND MSVC) ++ set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++endif() ++ + ################### + ## Find packages ## + ################### diff --git a/patch/ros-jazzy-lanelet2-python.win.patch b/patch/ros-jazzy-lanelet2-python.win.patch new file mode 100644 index 00000000..c3a792e3 --- /dev/null +++ b/patch/ros-jazzy-lanelet2-python.win.patch @@ -0,0 +1,15 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 00e06d76..b5c9bba9 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -52,6 +52,10 @@ mrt_add_library(${PROJECT_NAME} + SOURCES ${PROJECT_SOURCE_FILES_SRC} + ) + ++target_compile_options(${PROJECT_NAME} INTERFACE ++ $<$:/bigobj> ++) ++ + ############# + ## Install ## + ############# diff --git a/patch/ros-jazzy-lanelet2-routing.win.patch b/patch/ros-jazzy-lanelet2-routing.win.patch new file mode 100644 index 00000000..97835e5b --- /dev/null +++ b/patch/ros-jazzy-lanelet2-routing.win.patch @@ -0,0 +1,31 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index a1f08032..2b3291c3 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -3,6 +3,10 @@ set(MRT_PKG_VERSION 4.0.0) + cmake_minimum_required(VERSION 3.5.1) + project(lanelet2_routing) + ++if(WIN32 AND MSVC) ++ set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++endif() ++ + ################### + ## Find packages ## + ################### +diff --git a/src/RouteBuilder.cpp b/src/RouteBuilder.cpp +index 9eee0943..4ad61cbc 100644 +--- a/src/RouteBuilder.cpp ++++ b/src/RouteBuilder.cpp +@@ -237,9 +237,9 @@ class PathsOutOfRouteFinder { + constexpr auto Adjacent = + RelationType::Left | RelationType::Right | RelationType::AdjacentLeft | RelationType::AdjacentRight; + return std::any_of(inEdges.first, inEdges.second, +- [&](auto e) { return hasRelation(g, e) && has(*llts_, boost::source(e, g)); }) || ++ [&](auto e) { return hasRelation(g, e) && has(*llts_, boost::source(e, g)); }) || + std::any_of(outEdges.first, outEdges.second, +- [&](auto e) { return hasRelation(g, e) && has(*llts_, boost::target(e, g)); }); ++ [&](auto e) { return hasRelation(g, e) && has(*llts_, boost::target(e, g)); }); + }; + return std::all_of(path.begin(), path.end(), isAdjacentToRoute); + } diff --git a/patch/ros-jazzy-lanelet2-traffic-rules.win.patch b/patch/ros-jazzy-lanelet2-traffic-rules.win.patch new file mode 100644 index 00000000..70bfc502 --- /dev/null +++ b/patch/ros-jazzy-lanelet2-traffic-rules.win.patch @@ -0,0 +1,15 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 283286e6..a875a4a5 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -3,6 +3,10 @@ set(MRT_PKG_VERSION 4.0.0) + cmake_minimum_required(VERSION 3.5.1) + project(lanelet2_traffic_rules) + ++if(WIN32 AND MSVC) ++ set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++endif() ++ + ################### + ## Find packages ## + ################### diff --git a/patch/ros-jazzy-lanelet2-validation.win.patch b/patch/ros-jazzy-lanelet2-validation.win.patch new file mode 100644 index 00000000..05dd0665 --- /dev/null +++ b/patch/ros-jazzy-lanelet2-validation.win.patch @@ -0,0 +1,15 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 6eb87afe..277437ae 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -3,6 +3,10 @@ set(MRT_PKG_VERSION 4.0.0) + cmake_minimum_required(VERSION 3.5.1) + project(lanelet2_validation) + ++if(WIN32 AND MSVC) ++ set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) ++endif() ++ + ################### + ## Find packages ## + ################### diff --git a/patch/ros-jazzy-mrt-cmake-modules.patch b/patch/ros-jazzy-mrt-cmake-modules.patch new file mode 100644 index 00000000..ea30f88b --- /dev/null +++ b/patch/ros-jazzy-mrt-cmake-modules.patch @@ -0,0 +1,26 @@ +diff --git a/cmake/Modules/FindBoostPython.cmake b/cmake/Modules/FindBoostPython.cmake +index 409cfaf..a3d9984 100644 +--- a/cmake/Modules/FindBoostPython.cmake ++++ b/cmake/Modules/FindBoostPython.cmake +@@ -8,7 +8,7 @@ + if(PYTHON_VERSION) + set(_python_version ${PYTHON_VERSION}) + else() +- set(_python_version 2.7) ++ set(_python_version 3) + endif() + if(_python_version VERSION_EQUAL 3 AND CMAKE_VERSION VERSION_GREATER 3.15) + # we also need the subversion +diff --git a/CMakeLists.txt b/CMakeLists.txt +index aa99d8d..8327d4e 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -1,7 +1,7 @@ + cmake_minimum_required(VERSION 3.0.2) + project(mrt_cmake_modules) + +-if($ENV{ROS_VERSION} EQUAL 1) ++if(2 EQUAL 1) + find_package(catkin REQUIRED) + catkin_package(CFG_EXTRAS mrt_cmake_modules-extras.cmake) + else() diff --git a/vinca_linux_64.yaml b/vinca_linux_64.yaml index ff3299d3..6a21bd8a 100644 --- a/vinca_linux_64.yaml +++ b/vinca_linux_64.yaml @@ -92,5 +92,7 @@ packages_select_by_deps: - foxglove_compressed_video_transport - foxglove_msgs + - lanelet2 + patch_dir: patch rosdistro_snapshot: rosdistro_snapshot.yaml diff --git a/vinca_linux_aarch64.yaml b/vinca_linux_aarch64.yaml index ff3299d3..6a21bd8a 100644 --- a/vinca_linux_aarch64.yaml +++ b/vinca_linux_aarch64.yaml @@ -92,5 +92,7 @@ packages_select_by_deps: - foxglove_compressed_video_transport - foxglove_msgs + - lanelet2 + patch_dir: patch rosdistro_snapshot: rosdistro_snapshot.yaml diff --git a/vinca_osx.yaml b/vinca_osx.yaml index d0d74af2..7872bd13 100644 --- a/vinca_osx.yaml +++ b/vinca_osx.yaml @@ -101,5 +101,7 @@ packages_select_by_deps: - foxglove_compressed_video_transport - foxglove_msgs + - lanelet2 + patch_dir: patch rosdistro_snapshot: rosdistro_snapshot.yaml diff --git a/vinca_osx_arm64.yaml b/vinca_osx_arm64.yaml index fa576bda..ee62a6ae 100644 --- a/vinca_osx_arm64.yaml +++ b/vinca_osx_arm64.yaml @@ -101,5 +101,7 @@ packages_select_by_deps: - foxglove_compressed_video_transport - foxglove_msgs + - lanelet2 + patch_dir: patch rosdistro_snapshot: rosdistro_snapshot.yaml diff --git a/vinca_win.yaml b/vinca_win.yaml index 4c37e451..df660bb2 100644 --- a/vinca_win.yaml +++ b/vinca_win.yaml @@ -102,6 +102,8 @@ packages_select_by_deps: # - foxglove_compressed_video_transport - foxglove_msgs + - lanelet2 + patch_dir: patch rosdistro_snapshot: rosdistro_snapshot.yaml