Skip to content

Commit

Permalink
Removes parallel execution due to race conditions.
Browse files Browse the repository at this point in the history
Signed-off-by: Franco Cipollone <franco.c@ekumenlabs.com>
  • Loading branch information
francocipollone committed Feb 6, 2023
1 parent 1d2c300 commit 9f81200
Show file tree
Hide file tree
Showing 4 changed files with 2 additions and 9 deletions.
3 changes: 0 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,6 @@ message(STATUS "\n\n====== Finding 3rd Party Packages ======\n")
find_package(ament_cmake REQUIRED)
find_package(maliput REQUIRED)

# TODO(francocipollone): Remove this once we move to GCC 10.
find_package(TBB REQUIRED)

##############################################################################
# Project Configuration
##############################################################################
Expand Down
1 change: 0 additions & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
<doc_depend>ament_cmake_doxygen</doc_depend>

<depend>maliput</depend>
<depend>tbb</depend>

<test_depend>ament_cmake_clang_format</test_depend>
<test_depend>ament_cmake_gmock</test_depend>
Expand Down
2 changes: 0 additions & 2 deletions src/geometry/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,6 @@ target_link_libraries(geometry
PUBLIC
maliput::common
maliput::math
PRIVATE
TBB::tbb
)

##############################################################################
Expand Down
5 changes: 2 additions & 3 deletions src/geometry/utility/geometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,6 @@
#include <cmath>
#include <numeric>

#include <execution>
#include <maliput/common/range_validator.h>

namespace maliput_sparse {
Expand Down Expand Up @@ -354,7 +353,7 @@ ClosestPointResult3d GetClosestPoint(const LineString3d& line_string, const mali
segment_closest_point_result.distance = std::numeric_limits<double>::max();

const auto& segments = line_string.segments();
std::for_each(std::execution::par, segments.begin(), segments.end(), [&](const auto& segment) {
std::for_each(segments.begin(), segments.end(), [&](const auto& segment) {
const auto& start = line_string[segment.second.idx_start];
const auto& end = line_string[segment.second.idx_end];
const auto current_closest_point_res = GetClosestPointToSegment(Segment3d{start, end}, xyz, tolerance);
Expand All @@ -378,7 +377,7 @@ ClosestPointResult3d GetClosestPointUsing2dProjection(const LineString3d& line_s
segment_closest_point_result.distance = std::numeric_limits<double>::max();

const auto& segments = line_string.segments();
std::for_each(std::execution::par, segments.begin(), segments.end(), [&](const auto& segment) {
std::for_each(segments.begin(), segments.end(), [&](const auto& segment) {
const auto& start = line_string[segment.second.idx_start];
const auto& end = line_string[segment.second.idx_end];
const Segment2d segment_2d{To2D(start), To2D(end)};
Expand Down

0 comments on commit 9f81200

Please sign in to comment.