Skip to content

Commit 60bc493

Browse files
committed
[build] Enable tests with MSVC
1 parent e48dcb0 commit 60bc493

File tree

4 files changed

+34
-26
lines changed

4 files changed

+34
-26
lines changed

.github/workflows/ci_windows.yml

+2-1
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,8 @@ jobs:
3737

3838
- uses: johnwason/vcpkg-action@v6
3939
with:
40-
pkgs: assimp ccd eigen3 fcl fmt spdlog bullet3 coin-or-ipopt freeglut glfw3 nlopt ode opengl osg pagmo2 tinyxml2 urdfdom
40+
# TODO: Add ode and coin-or-ipopt
41+
pkgs: assimp ccd eigen3 fcl fmt spdlog bullet3 freeglut glfw3 nlopt opengl osg pagmo2 tinyxml2 urdfdom
4142
triplet: x64-windows
4243
revision: "2024.02.14"
4344
github-binarycache: true

dart/collision/bullet/BulletCollisionDetector.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -127,7 +127,7 @@ class BulletCollisionDetector : public CollisionDetector
127127
std::unique_ptr<BulletCollisionShape> createBulletCollisionShape(
128128
const dynamics::ConstShapePtr& shape);
129129

130-
/// This deleter is responsible for deleting BulletCollsionShape objects and
130+
/// This deleter is responsible for deleting BulletCollisionShape objects and
131131
/// removing them from mShapeMap when they are not shared by any
132132
/// CollisionObjects.
133133
class BulletCollisionShapeDeleter final

tests/CMakeLists.txt

+2-5
Original file line numberDiff line numberDiff line change
@@ -92,11 +92,8 @@ include_directories(${CMAKE_CURRENT_SOURCE_DIR})
9292
# fixed even after further changes are made
9393
# - "unit": low level tests for one or few classes and functions to verify that
9494
# they performs correctly as expected
95-
if(NOT MSVC)
96-
# Disabled due to limitied disk space in CI image
97-
add_subdirectory(integration)
98-
add_subdirectory(regression)
99-
endif()
95+
add_subdirectory(integration)
96+
add_subdirectory(regression)
10097
add_subdirectory(unit)
10198

10299
# Print tests

tests/integration/test_Collision.cpp

+29-19
Original file line numberDiff line numberDiff line change
@@ -424,32 +424,30 @@ void testSphereSphere(
424424

425425
collision::CollisionResult result;
426426

427-
simpleFrame1->setTranslation(Eigen::Vector3d::Zero());
428-
simpleFrame2->setTranslation(Eigen::Vector3d(2.0, 0.0, 0.0));
429-
430427
//----------------------------------------------------------------------------
431428
// Test 1: No contact
432429
//----------------------------------------------------------------------------
433430

431+
simpleFrame1->setTranslation(Eigen::Vector3d::Zero());
432+
simpleFrame2->setTranslation(Eigen::Vector3d(2.0, 0.0, 0.0));
434433
result.clear();
435434
EXPECT_FALSE(group->collide(option, &result));
436435
EXPECT_TRUE(result.getNumContacts() == 0u);
437436

438-
simpleFrame1->setTranslation(Eigen::Vector3d::Zero());
439-
simpleFrame2->setTranslation(Eigen::Vector3d(1.5, 0.0, 0.0));
440-
441437
//----------------------------------------------------------------------------
442438
// Test 2: Point contact
443439
//----------------------------------------------------------------------------
444440

441+
simpleFrame1->setTranslation(Eigen::Vector3d::Zero());
442+
simpleFrame2->setTranslation(Eigen::Vector3d(1.5 - tol, 0.0, 0.0));
445443
result.clear();
446444
EXPECT_TRUE(group->collide(option, &result));
447445
EXPECT_TRUE(result.getNumContacts() == 1u);
448446

449447
const auto& contact = result.getContact(0);
450448

451449
// Test contact location
452-
EXPECT_TRUE(contact.point.isApprox(Eigen::Vector3d::UnitX(), tol));
450+
EXPECT_TRUE(contact.point.isApprox(Eigen::Vector3d::UnitX(), 2.0 * tol));
453451

454452
// Test normal
455453
Eigen::Vector3d expectedNormal;
@@ -479,10 +477,10 @@ void testSphereSphere(
479477
if (cd->getType() == FCLCollisionDetector::getStaticType()) {
480478
EXPECT_FALSE(group->collide(option, &result));
481479
// FCL is not able to detect collisions when an object completely (strictly)
482-
// contanins the other object (no collisions between the hulls)
480+
// contains the other object (no collisions between the hulls)
483481
} else {
484482
EXPECT_TRUE(group->collide(option, &result));
485-
// TODO(JS): BulletCollsionDetector includes a bug related to this.
483+
// TODO(JS): BulletCollisionDetector includes a bug related to this.
486484
// (see #876)
487485
#if HAVE_BULLET
488486
if (cd->getType() != BulletCollisionDetector::getStaticType())
@@ -502,10 +500,13 @@ void testSphereSphere(
502500
//==============================================================================
503501
TEST_F(Collision, SphereSphere)
504502
{
505-
auto fcl_mesh_dart = FCLCollisionDetector::create();
506-
fcl_mesh_dart->setPrimitiveShapeType(FCLCollisionDetector::MESH);
507-
fcl_mesh_dart->setContactPointComputationMethod(FCLCollisionDetector::DART);
508-
testSphereSphere(fcl_mesh_dart);
503+
{
504+
SCOPED_TRACE("FCLCollisionDetector");
505+
auto fcl_mesh_dart = FCLCollisionDetector::create();
506+
fcl_mesh_dart->setPrimitiveShapeType(FCLCollisionDetector::MESH);
507+
fcl_mesh_dart->setContactPointComputationMethod(FCLCollisionDetector::DART);
508+
testSphereSphere(fcl_mesh_dart);
509+
}
509510

510511
// auto fcl_prim_fcl = FCLCollisionDetector::create();
511512
// fcl_prim_fcl->setPrimitiveShapeType(FCLCollisionDetector::MESH);
@@ -523,17 +524,26 @@ TEST_F(Collision, SphereSphere)
523524
// testSphereSphere(fcl_mesh_fcl);
524525

525526
#if HAVE_ODE
526-
auto ode = OdeCollisionDetector::create();
527-
testSphereSphere(ode);
527+
{
528+
SCOPED_TRACE("OdeCollisionDetector");
529+
auto ode = OdeCollisionDetector::create();
530+
testSphereSphere(ode);
531+
}
528532
#endif
529533

530534
#if HAVE_BULLET
531-
auto bullet = BulletCollisionDetector::create();
532-
testSphereSphere(bullet);
535+
{
536+
SCOPED_TRACE("BulletCollisionDetector");
537+
auto bullet = BulletCollisionDetector::create();
538+
testSphereSphere(bullet);
539+
}
533540
#endif
534541

535-
auto dart = DARTCollisionDetector::create();
536-
testSphereSphere(dart);
542+
{
543+
SCOPED_TRACE("BulletCollisionDetector");
544+
auto dart = DARTCollisionDetector::create();
545+
testSphereSphere(dart);
546+
}
537547
}
538548

539549
//==============================================================================

0 commit comments

Comments
 (0)