From 7acb48f62e1dbddfa5169697b385270502ab3ef6 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Wed, 16 Jan 2019 16:41:40 -0800 Subject: [PATCH] Support DART >= 6.6.2 --- CMakeLists.txt | 2 +- src/planner/World.cpp | 4 ++++ tests/statespace/dart/test_MetaSkeletonStateSpace.cpp | 4 ++++ tests/statespace/test_CartesianProduct.cpp | 4 ++++ tests/statespace/test_SE2.cpp | 4 ++++ tests/statespace/test_SE3.cpp | 4 ++++ tests/statespace/test_SO2.cpp | 4 ++++ tests/statespace/test_SO3.cpp | 4 ++++ 8 files changed, 29 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 750784ba52..08f0e062b3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -126,7 +126,7 @@ include(FindPkgConfig) find_package(Boost REQUIRED COMPONENTS filesystem) -find_package(DART 6.7.0 REQUIRED +find_package(DART 6.6.2 REQUIRED COMPONENTS optimizer-nlopt utils OPTIONAL_COMPONENTS utils-urdf # for 'perception' target CONFIG diff --git a/src/planner/World.cpp b/src/planner/World.cpp index 0472a7ccba..600546feb2 100644 --- a/src/planner/World.cpp +++ b/src/planner/World.cpp @@ -38,7 +38,11 @@ std::unique_ptr World::clone(const std::string& newName) const worldClone->mSkeletons.reserve(mSkeletons.size()); for (std::size_t i = 0; i < mSkeletons.size(); ++i) { +#if DART_VERSION_AT_LEAST(6,7,0) const auto clonedSkeleton = mSkeletons[i]->cloneSkeleton(); +#elif + const auto clonedSkeleton = mSkeletons[i]->clone(); +#endif clonedSkeleton->setConfiguration(mSkeletons[i]->getConfiguration()); worldClone->addSkeleton(std::move(clonedSkeleton)); } diff --git a/tests/statespace/dart/test_MetaSkeletonStateSpace.cpp b/tests/statespace/dart/test_MetaSkeletonStateSpace.cpp index b593f60d0d..8d5974181d 100644 --- a/tests/statespace/dart/test_MetaSkeletonStateSpace.cpp +++ b/tests/statespace/dart/test_MetaSkeletonStateSpace.cpp @@ -98,7 +98,11 @@ TEST(MetaSkeletonStateSpace, RevoluteJoint_CompatibleSkeletons) withBoundSpace.checkCompatibility(withoutBound.get()), std::invalid_argument); +#if DART_VERSION_AT_LEAST(6,7,0) auto withoutBoundClone = withoutBound->cloneSkeleton(); +#else + auto withoutBoundClone = withoutBound->clone(); +#endif EXPECT_TRUE(withoutBoundSpace.isCompatible(withoutBoundClone.get())); EXPECT_NO_THROW( withoutBoundSpace.checkCompatibility(withoutBoundClone.get())); diff --git a/tests/statespace/test_CartesianProduct.cpp b/tests/statespace/test_CartesianProduct.cpp index b169d20038..5851f57715 100644 --- a/tests/statespace/test_CartesianProduct.cpp +++ b/tests/statespace/test_CartesianProduct.cpp @@ -20,7 +20,11 @@ TEST(CartesianProduct, Clone) for (auto i = 0u; i < 5u; ++i) { auto s1 = space.createState(); +#if DART_VERSION_AT_LEAST(6,7,0) const auto angle = dart::math::Random::uniform(-M_PI, M_PI); +#else + const auto angle = dart::math::random(-M_PI, M_PI); +#endif s1.getSubStateHandle(0).fromAngle(angle); s1.getSubStateHandle(1).setValue(Eigen::Vector2d::Random()); diff --git a/tests/statespace/test_SE2.cpp b/tests/statespace/test_SE2.cpp index e28453aa0c..f5e7d52c8a 100644 --- a/tests/statespace/test_SE2.cpp +++ b/tests/statespace/test_SE2.cpp @@ -10,7 +10,11 @@ TEST(SE2, Clone) for (auto i = 0u; i < 5u; ++i) { +#if DART_VERSION_AT_LEAST(6,7,0) const auto angle = dart::math::Random::uniform(-M_PI, M_PI); +#else + const auto angle = dart::math::random(-M_PI, M_PI); +#endif Eigen::Isometry2d pose = Eigen::Isometry2d::Identity(); pose.rotate(Eigen::Rotation2Dd(angle)); pose.translation() = Eigen::Vector2d::Random(); diff --git a/tests/statespace/test_SE3.cpp b/tests/statespace/test_SE3.cpp index 68fbb42e58..635ad87bb8 100644 --- a/tests/statespace/test_SE3.cpp +++ b/tests/statespace/test_SE3.cpp @@ -12,7 +12,11 @@ TEST(SE3, Clone) for (auto i = 0u; i < 5u; ++i) { Eigen::Isometry3d pose = Eigen::Isometry3d::Identity(); +#if DART_VERSION_AT_LEAST(6,7,0) const auto angle = dart::math::Random::uniform(-M_PI, M_PI); +#else + const auto angle = dart::math::random(-M_PI, M_PI); +#endif const auto axis = Eigen::Vector3d::Random().normalized(); const auto angleAxis = Eigen::AngleAxisd(angle, axis); pose.linear() = angleAxis.toRotationMatrix(); diff --git a/tests/statespace/test_SO2.cpp b/tests/statespace/test_SO2.cpp index 83510bf704..083c760ca1 100644 --- a/tests/statespace/test_SO2.cpp +++ b/tests/statespace/test_SO2.cpp @@ -33,7 +33,11 @@ TEST(SO2, Clone) for (auto i = 0u; i < 5u; ++i) { +#if DART_VERSION_AT_LEAST(6,7,0) const auto angle = dart::math::Random::uniform(-M_PI, M_PI); +#else + const auto angle = dart::math::random(-M_PI, M_PI); +#endif auto s1 = so2.createState(); s1.fromAngle(angle); diff --git a/tests/statespace/test_SO3.cpp b/tests/statespace/test_SO3.cpp index fae78f890c..d611bca371 100644 --- a/tests/statespace/test_SO3.cpp +++ b/tests/statespace/test_SO3.cpp @@ -10,7 +10,11 @@ TEST(SO3, Clone) for (auto i = 0u; i < 5u; ++i) { +#if DART_VERSION_AT_LEAST(6,7,0) const auto angle = dart::math::Random::uniform(-M_PI, M_PI); +#else + const auto angle = dart::math::random(-M_PI, M_PI); +#endif const auto axis = Eigen::Vector3d::Random().normalized(); const auto angleAxis = Eigen::AngleAxisd(angle, axis); const Eigen::Quaterniond quat(angleAxis);