fzi-forschungszentrum-informatik / Lanelet2

Map handling framework for automated driving
BSD 3-Clause "New" or "Revised" License
800 stars 327 forks source link

Help with boost 1.71 geometry compiler error #115

Closed kgreenek closed 4 years ago

kgreenek commented 4 years ago

This not a bug report, so much as a request for help.

I'm attempting to build lanelet2_routing with boost 1.71. I'm building in a bazel mono-repo, so the environment is a bit different. I think the issue is boost-version-related though.

I'm getting this deeply-nested template compiler error. I'm not very familiar with boost geometry and have been bashing my head on this for a while. It looks like something somewhere needs to be passed a 4th arg where it's only being passed 3.

Any help or insight appreciated. Thanks!

In file included from external/boost/boost/geometry/views/box_view.hpp:22:0,
                 from external/boost/boost/geometry/views/detail/range_type.hpp:25,
                 from external/boost/boost/geometry/views/detail/normalized_view.hpp:28,
                 from external/boost/boost/geometry/algorithms/detail/within/point_in_geometry.hpp:41,
                 from external/boost/boost/geometry/algorithms/detail/within/multi_point.hpp:24,
                 from external/boost/boost/geometry/algorithms/detail/within/implementation.hpp:44,
                 from external/boost/boost/geometry/algorithms/detail/covered_by/implementation.hpp:25,
                 from external/boost/boost/geometry/algorithms/covered_by.hpp:24,
                 from external/boost/boost/geometry/algorithms/detail/disjoint/areal_areal.hpp:26,
                 from external/boost/boost/geometry/algorithms/detail/disjoint/implementation.hpp:25,
                 from external/boost/boost/geometry/algorithms/detail/intersects/implementation.hpp:27,
                 from external/boost/boost/geometry/algorithms/intersects.hpp:25,
                 from external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LineString.h:2,
                 from external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Polygon.h:5,
                 from external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Area.h:5,
                 from external/lanelet2/lanelet2_routing/src/RoutingGraphBuilder.cpp:3:
external/boost/boost/geometry/algorithms/assign.hpp: In instantiation of 'void boost::geometry::assign_values(Geometry&, const Type&, const Type&) [with Geometry = boost::geometry::model::point<long long int, 3, boost::geometry::cs::cartesian>; Type = long long int]':
external/boost/boost/geometry/policies/robustness/get_rescale_policy.hpp:92:18:   required from 'void boost::geometry::detail::get_rescale_policy::scale_box_to_integer_range(const Box&, Point&, RobustPoint&, Factor&) [with Box = boost::geometry::model::box<Eigen::Matrix<double, 3, 1> >; Point = Eigen::Matrix<double, 3, 1>; RobustPoint = boost::geometry::model::point<long long int, 3, boost::geometry::cs::cartesian>; Factor = double]'
external/boost/boost/geometry/policies/robustness/get_rescale_policy.hpp:166:31:   required from 'void boost::geometry::detail::get_rescale_policy::init_rescale_policy(const Geometry1&, const Geometry2&, Point&, RobustPoint&, Factor&, const EnvelopeStrategy1&, const EnvelopeStrategy2&) [with Point = Eigen::Matrix<double, 3, 1>; RobustPoint = boost::geometry::model::point<long long int, 3, boost::geometry::cs::cartesian>; Geometry1 = lanelet::CompoundHybridPolygon3d; Geometry2 = lanelet::CompoundHybridPolygon3d; Factor = double; EnvelopeStrategy1 = boost::geometry::strategy::envelope::cartesian<>; EnvelopeStrategy2 = boost::geometry::strategy::envelope::cartesian<>]'
external/boost/boost/geometry/policies/robustness/get_rescale_policy.hpp:242:28:   required from 'static Policy boost::geometry::detail::get_rescale_policy::get_rescale_policy<Policy>::apply(const Geometry1&, const Geometry2&, const EnvelopeStrategy1&, const EnvelopeStrategy2&) [with Geometry1 = lanelet::CompoundHybridPolygon3d; Geometry2 = lanelet::CompoundHybridPolygon3d; EnvelopeStrategy1 = boost::geometry::strategy::envelope::cartesian<>; EnvelopeStrategy2 = boost::geometry::strategy::envelope::cartesian<>; Policy = boost::geometry::detail::robust_policy<Eigen::Matrix<double, 3, 1>, boost::geometry::model::point<long long int, 3, boost::geometry::cs::cartesian>, double>]'
external/boost/boost/geometry/policies/robustness/get_rescale_policy.hpp:518:21:   required from 'Policy boost::geometry::get_rescale_policy(const Geometry1&, const Geometry2&, const IntersectionStrategy&) [with Policy = boost::geometry::detail::robust_policy<Eigen::Matrix<double, 3, 1>, boost::geometry::model::point<long long int, 3, boost::geometry::cs::cartesian>, double>; Geometry1 = lanelet::CompoundHybridPolygon3d; Geometry2 = lanelet::CompoundHybridPolygon3d; IntersectionStrategy = boost::geometry::strategy::intersection::cartesian_segments<>]'
external/boost/boost/geometry/algorithms/detail/relate/turns.hpp:113:64:   required from 'static void boost::geometry::detail::relate::turns::get_turns<Geometry1, Geometry2, GetTurnPolicy>::apply(Turns&, const Geometry1&, const Geometry2&, InterruptPolicy&, const IntersectionStrategy&) [with Turns = std::vector<boost::geometry::detail::overlay::turn_info<Eigen::Matrix<double, 3, 1>, boost::geometry::segment_ratio<long long int>, boost::geometry::detail::overlay::turn_operation<Eigen::Matrix<double, 3, 1>, boost::geometry::segment_ratio<long long int> >, boost::array<boost::geometry::detail::overlay::turn_operation<Eigen::Matrix<double, 3, 1>, boost::geometry::segment_ratio<long long int> >, 2> >, std::allocator<boost::geometry::detail::overlay::turn_info<Eigen::Matrix<double, 3, 1>, boost::geometry::segment_ratio<long long int>, boost::geometry::detail::overlay::turn_operation<Eigen::Matrix<double, 3, 1>, boost::geometry::segment_ratio<long long int> >, boost::array<boost::geometry::detail::overlay::turn_operation<Eigen::Matrix<double, 3, 1>, boost::geometry::segment_ratio<long long int> >, 2> > > >; InterruptPolicy = boost::geometry::detail::relate::areal_areal<lanelet::CompoundHybridPolygon3d, lanelet::CompoundHybridPolygon3d>::interrupt_policy_areal_areal<boost::geometry::detail::relate::static_mask_handler<boost::geometry::de9im::static_mask<'T', '*', '*', '*', '*', '*', '*', '*', '*'>, true> >; IntersectionStrategy = boost::geometry::strategy::intersection::cartesian_segments<>; Geometry1 = lanelet::CompoundHybridPolygon3d; Geometry2 = lanelet::CompoundHybridPolygon3d; GetTurnPolicy = boost::geometry::detail::get_turns::get_turn_info_type<lanelet::CompoundHybridPolygon3d, lanelet::CompoundHybridPolygon3d, boost::geometry::detail::relate::turns::assign_policy<>, boost::geometry::ring_tag, boost::geometry::ring_tag, boost::geometry::areal_tag, boost::geometry::areal_tag>]'
external/boost/boost/geometry/algorithms/detail/relate/areal_areal.hpp:234:54:   required from 'static void boost::geometry::detail::relate::areal_areal<Geometry1, Geometry2>::apply(const Geometry1&, const Geometry2&, Result&, const IntersectionStrategy&) [with Result = boost::geometry::detail::relate::static_mask_handler<boost::geometry::de9im::static_mask<'T', '*', '*', '*', '*', '*', '*', '*', '*'>, true>; IntersectionStrategy = boost::geometry::strategy::intersection::cartesian_segments<>; Geometry1 = lanelet::CompoundHybridPolygon3d; Geometry2 = lanelet::CompoundHybridPolygon3d]'
external/boost/boost/geometry/algorithms/detail/relate/interface.hpp:227:21:   required from 'static void boost::geometry::resolve_strategy::relate::apply(const Geometry1&, const Geometry2&, ResultHandler&, boost::geometry::default_strategy) [with Geometry1 = lanelet::CompoundHybridPolygon3d; Geometry2 = lanelet::CompoundHybridPolygon3d; ResultHandler = boost::geometry::detail::relate::static_mask_handler<boost::geometry::de9im::static_mask<'T', '*', '*', '*', '*', '*', '*', '*', '*'>, true>]'
external/boost/boost/geometry/algorithms/detail/relate/interface.hpp:255:40:   required from 'static bool boost::geometry::resolve_variant::relate<Geometry1, Geometry2>::apply(const Geometry1&, const Geometry2&, const Mask&, const Strategy&) [with Mask = boost::geometry::de9im::static_mask<'T', '*', '*', '*', '*', '*', '*', '*', '*'>; Strategy = boost::geometry::default_strategy; Geometry1 = lanelet::CompoundHybridPolygon3d; Geometry2 = lanelet::CompoundHybridPolygon3d]'
external/boost/boost/geometry/algorithms/detail/relate/interface.hpp:416:21:   required from 'bool boost::geometry::relate(const Geometry1&, const Geometry2&, const Mask&) [with Geometry1 = lanelet::CompoundHybridPolygon3d; Geometry2 = lanelet::CompoundHybridPolygon3d; Mask = boost::geometry::de9im::static_mask<'T', '*', '*', '*', '*', '*', '*', '*', '*'>]'
external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Polygon.h:61:33:   required from 'lanelet::IfPoly<PolygonT, bool> lanelet::geometry::overlaps2d(const Polygon2dT&, const Polygon2dT&) [with Polygon2dT = lanelet::CompoundPolygon3d; lanelet::IfPoly<PolygonT, bool> = bool]'
external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Area.h:43:20:   required from 'lanelet::IfAr<AreaT, bool> lanelet::geometry::overlaps2d(const AreaT&, const AreaT&) [with AreaT = lanelet::ConstArea; lanelet::IfAr<AreaT, bool> = bool]'
external/lanelet2/lanelet2_routing/src/RoutingGraphBuilder.cpp:308:71:   required from here
external/boost/boost/geometry/algorithms/assign.hpp:156:17: error: no matching function for call to 'boost::geometry::dispatch::assign<boost::geometry::point_tag, boost::geometry::model::point<long long int, 3, boost::geometry::cs::cartesian>, 3>::apply(boost::geometry::model::point<long long int, 3, boost::geometry::cs::cartesian>&, const long long int&, const long long int&)'
     dispatch::assign
     ~~~~~~~~~~~~~~~~
         <
         ~        
             typename tag<Geometry>::type,
             ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
             Geometry,
             ~~~~~~~~~
             geometry::dimension<Geometry>::type::value
             ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
         >::apply(geometry, c1, c2);
         ~~~~~~~~^~~~~~~~~~~~~~~~~~
In file included from external/boost/boost/geometry/algorithms/detail/assign_box_corners.hpp:21:0,
                 from external/boost/boost/geometry/algorithms/assign.hpp:32,
                 from external/boost/boost/geometry/views/box_view.hpp:22,
                 from external/boost/boost/geometry/views/detail/range_type.hpp:25,
                 from external/boost/boost/geometry/views/detail/normalized_view.hpp:28,
                 from external/boost/boost/geometry/algorithms/detail/within/point_in_geometry.hpp:41,
                 from external/boost/boost/geometry/algorithms/detail/within/multi_point.hpp:24,
                 from external/boost/boost/geometry/algorithms/detail/within/implementation.hpp:44,
                 from external/boost/boost/geometry/algorithms/detail/covered_by/implementation.hpp:25,
                 from external/boost/boost/geometry/algorithms/covered_by.hpp:24,
                 from external/boost/boost/geometry/algorithms/detail/disjoint/areal_areal.hpp:26,
                 from external/boost/boost/geometry/algorithms/detail/disjoint/implementation.hpp:25,
                 from external/boost/boost/geometry/algorithms/detail/intersects/implementation.hpp:27,
                 from external/boost/boost/geometry/algorithms/intersects.hpp:25,
                 from external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LineString.h:2,
                 from external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Polygon.h:5,
                 from external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Area.h:5,
                 from external/lanelet2/lanelet2_routing/src/RoutingGraphBuilder.cpp:3:
external/boost/boost/geometry/algorithms/detail/assign_values.hpp:283:24: note: candidate: template<class T> static void boost::geometry::dispatch::assign<boost::geometry::point_tag, Point, 3>::apply(Point&, const T&, const T&, const T&) [with T = T; Point = boost::geometry::model::point<long long int, 3, boost::geometry::cs::cartesian>]
     static inline void apply(Point& point, T const& c1, T const& c2, T const& c3)
                        ^~~~~
external/boost/boost/geometry/algorithms/detail/assign_values.hpp:283:24: note:   template argument deduction/substitution failed:
In file included from external/boost/boost/geometry/views/box_view.hpp:22:0,
                 from external/boost/boost/geometry/views/detail/range_type.hpp:25,
                 from external/boost/boost/geometry/views/detail/normalized_view.hpp:28,
                 from external/boost/boost/geometry/algorithms/detail/within/point_in_geometry.hpp:41,
                 from external/boost/boost/geometry/algorithms/detail/within/multi_point.hpp:24,
                 from external/boost/boost/geometry/algorithms/detail/within/implementation.hpp:44,
                 from external/boost/boost/geometry/algorithms/detail/covered_by/implementation.hpp:25,
                 from external/boost/boost/geometry/algorithms/covered_by.hpp:24,
                 from external/boost/boost/geometry/algorithms/detail/disjoint/areal_areal.hpp:26,
                 from external/boost/boost/geometry/algorithms/detail/disjoint/implementation.hpp:25,
                 from external/boost/boost/geometry/algorithms/detail/intersects/implementation.hpp:27,
                 from external/boost/boost/geometry/algorithms/intersects.hpp:25,
                 from external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LineString.h:2,
                 from external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Polygon.h:5,
                 from external/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Area.h:5,
                 from external/lanelet2/lanelet2_routing/src/RoutingGraphBuilder.cpp:3:
external/boost/boost/geometry/algorithms/assign.hpp:156:17: note:   candidate expects 4 arguments, 3 provided
     dispatch::assign
     ~~~~~~~~~~~~~~~~
         <
         ~        
             typename tag<Geometry>::type,
             ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
             Geometry,
             ~~~~~~~~~
             geometry::dimension<Geometry>::type::value
             ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
         >::apply(geometry, c1, c2);
poggenhans commented 4 years ago

Strange that boost 1.71 refuses to compile this all of a sudden but your observation seems to be correct that there are 3d types passed to a 2d function. Might be that there was a bug in boost::geometry that this case wasn't detected and that got fixed.

Can you try if applying this patch solves the problem for you?

kgreenek commented 4 years ago

Aha I think you are right that boost must have fixed a small bug that broke this.

That patch didn't do the trick, but doing the same thing in Polygon.h did! I sent out a PR (#116).

poggenhans commented 4 years ago

Thanks for investigating! My patch didn't work because there was a second location where overlaps2d was called with a 3d type. Your fix works as well, but it is not the solution I was looking for, because overlaps2d shouldn't be called with a 3d type in the first place.

I fixed these issues now with 84312718b1125bc8ccfce72e647b1e3b0f56467b. It should work for you too because a static_assert now makes sure overlaps2d is never called with a 3d type.

kgreenek commented 4 years ago

Awesome! Thank you!