Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
34 commits
Select commit Hold shift + click to select a range
99b7bd7
Update OctoMap to latest release (1.10.0)
mwoehlke-kitware Jan 26, 2026
444d2da
Correct uninitialized local variable
SeanCurtis-TRI Jan 26, 2026
6569bef
Unused variable
SeanCurtis-TRI Jan 27, 2026
417a030
Temporarily disable Debug build
SeanCurtis-TRI Jan 27, 2026
c55b685
Undo a bad "using std::move" -- made clang angry.
SeanCurtis-TRI Jan 27, 2026
b4896e9
Restore debug build to linux CI
SeanCurtis-TRI Jan 27, 2026
9c9b6be
Build octomap with in common release with FCL
SeanCurtis-TRI Jan 27, 2026
17ecab9
Apparently mac needs to be told to use modern C++
SeanCurtis-TRI Jan 27, 2026
e5f9ab8
Possibly correct yaml
SeanCurtis-TRI Jan 28, 2026
392c76f
Merge branch 'master' into update-octomap
SeanCurtis-TRI Jan 28, 2026
94877e9
Trying to clean up yaml....again
SeanCurtis-TRI Jan 28, 2026
9305217
Tweak workflow inputs
SeanCurtis-TRI Jan 28, 2026
4717839
Revert efforts to tweak build parameters
SeanCurtis-TRI Jan 28, 2026
87ce109
Missed part of the reversion
SeanCurtis-TRI Jan 28, 2026
277a5a5
Small convenience tweaks
SeanCurtis-TRI Jan 28, 2026
bfe49eb
Advance C++ standard to 17
SeanCurtis-TRI Jan 28, 2026
fc94947
Merge branch 'master' into update-octomap
SeanCurtis-TRI Jan 28, 2026
8a56785
Upgrade mac to 15 (sequoia)
SeanCurtis-TRI Jan 28, 2026
ce8f417
When building octomap on apple, don't let warnings be errors
SeanCurtis-TRI Jan 28, 2026
ec3fb40
Second attempt at disabling warning/error
SeanCurtis-TRI Jan 28, 2026
de01c87
Silence all the warnings
SeanCurtis-TRI Jan 28, 2026
b514f02
Octomap triggers AppleClang warnings
SeanCurtis-TRI Jan 28, 2026
4ad757c
More tweaks to octomap build
SeanCurtis-TRI Jan 28, 2026
557afe2
Back mac back down to 14...
SeanCurtis-TRI Jan 28, 2026
cab7a6a
Restore osx15 and pin to eigen 3.4.0
SeanCurtis-TRI Jan 28, 2026
d4267e2
Patch brew rcipe
SeanCurtis-TRI Jan 28, 2026
479c1ff
Adapting to mac CI failure
SeanCurtis-TRI Jan 29, 2026
c603a12
Remove mac entirely
SeanCurtis-TRI Jan 29, 2026
79d241d
Oops...took too much away.
SeanCurtis-TRI Jan 29, 2026
f6548c5
Upgrade windows to use eigen compatible with c++ 17
SeanCurtis-TRI Jan 29, 2026
3aa2d31
Eigen 3.4.1 may have been too aggressive for windows
SeanCurtis-TRI Jan 29, 2026
a696435
More windows accommodation
SeanCurtis-TRI Jan 29, 2026
66f8421
Windows grousing
SeanCurtis-TRI Jan 29, 2026
2eb90bf
Leave windows alone
SeanCurtis-TRI Feb 2, 2026
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 4 additions & 12 deletions .github/workflows/all_ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -39,18 +39,10 @@ jobs:
compiler: ${{ matrix.compiler }}
build: ${{ matrix.build }}

mac:
strategy:
matrix:
compiler: [clang]
build: [Release, Debug]
os: ['macos-14']
uses: ./.github/workflows/generic_ci.yml
with:
install-name: 'install_osx.sh'
os: ${{ matrix.os }}
compiler: ${{ matrix.compiler }}
build: ${{ matrix.build }}
# TODO: the mac os jobs have been removed as part of
# https://github.com/flexible-collision-library/fcl/pull/659. Getting FCL to
# successfully build and pass tests on mac os is still an open issue. See
# https://github.com/flexible-collision-library/fcl/issues/661.

# TODO:
# - Revisit coveralls.
Expand Down
5 changes: 5 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
## FCL 0

* Breaking changes

* Macosx is no longer part of CI. [659](https://github.com/flexible-collision-library/fcl/pull/659)
* See Issue [661](https://github.com/flexible-collision-library/fcl/issues/661) on how to restore it.

### FCL 0.7.0 (2021-09-09)

* Breaking changes
Expand Down
8 changes: 7 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -283,7 +283,7 @@ if(FCL_WITH_OCTOMAP)
endif()

set(FCL_HAVE_OCTOMAP 1)
message(STATUS "FCL uses OctoMap")
message(STATUS "FCL uses OctoMap ${OCTOMAP_VERSION}")
set(PKG_EXTERNAL_DEPS "${PKG_EXTERNAL_DEPS} octomap")
else()
message(STATUS "FCL does not use OctoMap")
Expand Down Expand Up @@ -342,7 +342,13 @@ add_subdirectory(include/fcl)

set(PKG_DESC "Flexible Collision Library")

if(WIN32)
# It's not clear what is necessary to make C++17 and eigen play together nicely
# on windows. TODO: Figure this out.
set(CMAKE_CXX_STANDARD 14)
else()
set(CMAKE_CXX_STANDARD 17)
endif()

configure_file(fcl.pc.in fcl.pc @ONLY)

Expand Down
9 changes: 7 additions & 2 deletions ci/install_linux.sh
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,14 @@ sudo apt-get -qq --yes --force-yes install libccd-dev
# Octomap
git clone https://github.com/OctoMap/octomap
cd octomap
git checkout tags/v1.8.0
git checkout tags/v1.10.0
mkdir build
cd build
cmake ..
cmake \
-DBUILD_DYNAMICETD3D_SUBPROJECT=off \
-DBUILD_OCTOVIS_SUBPROJECT=off \
-DCMAKE_BUILD_TYPE=Release \
-DCMAKE_POLICY_VERSION_MINIMUM=3.10 \
..
make
sudo make install
12 changes: 10 additions & 2 deletions ci/install_osx.sh
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
# Note: this file is vestigial until issue 661 is resolved and macos CI builds
# are restored.

brew update > /dev/null

brew install git
Expand All @@ -8,9 +11,14 @@ brew install libccd
# Octomap
git clone https://github.com/OctoMap/octomap
cd octomap
git checkout tags/v1.8.0
git checkout tags/v1.10.0
mkdir build
cd build
cmake ..
cmake \
-DBUILD_DYNAMICETD3D_SUBPROJECT=off \
-DBUILD_OCTOVIS_SUBPROJECT=off \
-DCMAKE_BUILD_TYPE=Release \
-DCMAKE_POLICY_VERSION_MINIMUM=3.10 \
..
make
sudo make install
4 changes: 2 additions & 2 deletions test/geometry/shape/test_convex.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -778,7 +778,7 @@ class TessellatedSphere final : public Polytope<double> {
public:
TessellatedSphere() : Polytope<double>(1.0) {
// The angle between the latitude lines measured along the prime meridian.
const double dphi = M_PI / 8;
const double dphi = constants<double>::pi() / 8;
auto slice_height = [dphi](int slice_index) {
// Assumes 1 <= slice_index < 8.
return std::cos(slice_index * dphi);
Expand All @@ -791,7 +791,7 @@ class TessellatedSphere final : public Polytope<double> {
vertices_->push_back({0, 0, 1});
// Now create the bands of vertices between slices 1 & 2, 2 & 3, etc.
// The angle between the longitude lines measured along the equator.
const double dtheta = 2 * M_PI / 8;
const double dtheta = 2 * constants<double>::pi() / 8;
for (int slice = 1; slice < 8; ++slice) {
double z = slice_height(slice);
double r = slice_radius(slice);
Expand Down
5 changes: 3 additions & 2 deletions test/test_fcl_capsule_capsule.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -604,7 +604,8 @@ class CapsuleCapsuleSegmentTest : public ::testing::Test {

detail::capsuleCapsuleDistance(this->c1_, this->X_FC1_, this->c2_,
this->X_FC2_, &distance, &p_FW1, &p_FW2);
const auto eps = constants<S>::eps_78();
// Slightly looser tolerance to accommodate multiple platforms.
const auto eps = constants<S>::eps_34();
using std::abs;
S error = abs(distance - this->expected_distance_);
if (error > eps) {
Expand Down Expand Up @@ -683,7 +684,7 @@ class CapsuleCapsuleSegmentTest : public ::testing::Test {

Transform3<S> X_TC1 = Transform3<S>::Identity();
Transform3<S> X_TC2 = Transform3<S>::Identity();
// Position C2 so that the lower end of its center lines is at the origin
// Position C2 so that the lower end of its center line is at the origin
// and overlaps with the upper end of C1's center line.
X_TC2.translation() << S(0), S(0), c2_.lz / S(2);

Expand Down
12 changes: 6 additions & 6 deletions test/test_fcl_geometric_shapes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3947,27 +3947,27 @@ void test_shapeDistance_conecylinder()
S dist;

res = solver1<S>().shapeDistance(s1, Transform3<S>::Identity(), s2, Transform3<S>::Identity(), &dist);
EXPECT_TRUE(dist < 0);
EXPECT_LT(dist, 0);
EXPECT_FALSE(res);

res = solver1<S>().shapeDistance(s1, transform, s2, transform, &dist);
EXPECT_TRUE(dist < 0);
EXPECT_LT(dist, 0);
EXPECT_FALSE(res);

res = solver1<S>().shapeDistance(s1, Transform3<S>::Identity(), s2, Transform3<S>(Translation3<S>(Vector3<S>(10.1, 0, 0))), &dist);
EXPECT_TRUE(fabs(dist - 0.1) < 0.01);
EXPECT_NEAR(dist - 0.1, 0, 0.01);
EXPECT_TRUE(res);

res = solver1<S>().shapeDistance(s1, transform, s2, transform * Transform3<S>(Translation3<S>(Vector3<S>(10.1, 0, 0))), &dist);
EXPECT_TRUE(fabs(dist - 0.1) < 0.02);
EXPECT_NEAR(dist - 0.1, 0, 0.02);
EXPECT_TRUE(res);

res = solver1<S>().shapeDistance(s1, Transform3<S>::Identity(), s2, Transform3<S>(Translation3<S>(Vector3<S>(40, 0, 0))), &dist);
EXPECT_TRUE(fabs(dist - 30) < 0.01);
EXPECT_NEAR(dist - 30, 0, 0.01);
EXPECT_TRUE(res);

res = solver1<S>().shapeDistance(s1, transform, s2, transform * Transform3<S>(Translation3<S>(Vector3<S>(40, 0, 0))), &dist);
EXPECT_TRUE(fabs(dist - 30) < 0.1);
EXPECT_NEAR(dist - 30, 0, 0.01);
EXPECT_TRUE(res);
}

Expand Down