From 15eb6c9917dbc35a1f1b8f08d421298b34ec6155 Mon Sep 17 00:00:00 2001 From: Michael Koval Date: Fri, 22 Apr 2016 17:33:32 -0400 Subject: [PATCH] Renamed OMPLPlanner -> Planner. --- .../ompl/{OMPLPlanner.hpp => Planner.hpp} | 2 +- ...{OMPLPlanner-impl.hpp => Planner-impl.hpp} | 0 aikido/src/planner/ompl/CMakeLists.txt | 2 +- .../ompl/{OMPLPlanner.cpp => Planner.cpp} | 2 +- aikido/tests/planner/ompl/OMPLTestHelpers.hpp | 2 +- .../planner/ompl/test_GeometricStateSpace.cpp | 2 +- aikido/tests/planner/ompl/test_GoalRegion.cpp | 6 +-- .../tests/planner/ompl/test_OMPLGoalSets.cpp | 2 +- .../tests/planner/ompl/test_OMPLPlanner.cpp | 46 +++++++++---------- .../tests/planner/ompl/test_StateSampler.cpp | 4 +- .../planner/ompl/test_ValidityChecker.cpp | 6 +-- 11 files changed, 37 insertions(+), 37 deletions(-) rename aikido/include/aikido/planner/ompl/{OMPLPlanner.hpp => Planner.hpp} (99%) rename aikido/include/aikido/planner/ompl/detail/{OMPLPlanner-impl.hpp => Planner-impl.hpp} (100%) rename aikido/src/planner/ompl/{OMPLPlanner.cpp => Planner.cpp} (99%) diff --git a/aikido/include/aikido/planner/ompl/OMPLPlanner.hpp b/aikido/include/aikido/planner/ompl/Planner.hpp similarity index 99% rename from aikido/include/aikido/planner/ompl/OMPLPlanner.hpp rename to aikido/include/aikido/planner/ompl/Planner.hpp index c1e822de1b..58260df039 100644 --- a/aikido/include/aikido/planner/ompl/OMPLPlanner.hpp +++ b/aikido/include/aikido/planner/ompl/Planner.hpp @@ -133,6 +133,6 @@ trajectory::TrajectoryPtr planOMPL(const ::ompl::base::PlannerPtr &_planner, } // namespace planner } // namespace aikido -#include "detail/OMPLPlanner-impl.hpp" +#include "detail/Planner-impl.hpp" #endif diff --git a/aikido/include/aikido/planner/ompl/detail/OMPLPlanner-impl.hpp b/aikido/include/aikido/planner/ompl/detail/Planner-impl.hpp similarity index 100% rename from aikido/include/aikido/planner/ompl/detail/OMPLPlanner-impl.hpp rename to aikido/include/aikido/planner/ompl/detail/Planner-impl.hpp diff --git a/aikido/src/planner/ompl/CMakeLists.txt b/aikido/src/planner/ompl/CMakeLists.txt index 819991571d..38a4e63b17 100644 --- a/aikido/src/planner/ompl/CMakeLists.txt +++ b/aikido/src/planner/ompl/CMakeLists.txt @@ -1,7 +1,7 @@ aikido_add_library("${PROJECT_NAME}_planner_ompl" GeometricStateSpace.cpp GoalRegion.cpp - OMPLPlanner.cpp + Planner.cpp StateSampler.cpp StateValidityChecker.cpp ) diff --git a/aikido/src/planner/ompl/OMPLPlanner.cpp b/aikido/src/planner/ompl/Planner.cpp similarity index 99% rename from aikido/src/planner/ompl/OMPLPlanner.cpp rename to aikido/src/planner/ompl/Planner.cpp index f91f368e14..2411e6274e 100644 --- a/aikido/src/planner/ompl/OMPLPlanner.cpp +++ b/aikido/src/planner/ompl/Planner.cpp @@ -1,4 +1,4 @@ -#include +#include #include #include diff --git a/aikido/tests/planner/ompl/OMPLTestHelpers.hpp b/aikido/tests/planner/ompl/OMPLTestHelpers.hpp index fe43fc2b15..dd3817cb22 100644 --- a/aikido/tests/planner/ompl/OMPLTestHelpers.hpp +++ b/aikido/tests/planner/ompl/OMPLTestHelpers.hpp @@ -163,7 +163,7 @@ class FailedSampleGenerator : public aikido::constraint::SampleGenerator { aikido::statespace::StateSpacePtr mStateSpace; }; -class OMPLPlannerTest : public ::testing::Test +class PlannerTest : public ::testing::Test { public: virtual void SetUp() diff --git a/aikido/tests/planner/ompl/test_GeometricStateSpace.cpp b/aikido/tests/planner/ompl/test_GeometricStateSpace.cpp index 52c604b406..71b8c8e25c 100644 --- a/aikido/tests/planner/ompl/test_GeometricStateSpace.cpp +++ b/aikido/tests/planner/ompl/test_GeometricStateSpace.cpp @@ -4,7 +4,7 @@ using aikido::planner::ompl::GeometricStateSpace; using StateSpace = aikido::statespace::dart::MetaSkeletonStateSpace; -class GeometricStateSpaceTest : public OMPLPlannerTest +class GeometricStateSpaceTest : public PlannerTest { public: void constructStateSpace() diff --git a/aikido/tests/planner/ompl/test_GoalRegion.cpp b/aikido/tests/planner/ompl/test_GoalRegion.cpp index fa3c8b74cb..262c204b71 100644 --- a/aikido/tests/planner/ompl/test_GoalRegion.cpp +++ b/aikido/tests/planner/ompl/test_GoalRegion.cpp @@ -1,18 +1,18 @@ #include "OMPLTestHelpers.hpp" #include "../../constraint/MockConstraints.hpp" #include -#include +#include using aikido::planner::ompl::GeometricStateSpace; using aikido::planner::ompl::GoalRegion; using StateSpace = aikido::statespace::dart::MetaSkeletonStateSpace; -class GoalRegionTest : public OMPLPlannerTest +class GoalRegionTest : public PlannerTest { public: virtual void SetUp() { - OMPLPlannerTest::SetUp(); + PlannerTest::SetUp(); gSpace = std::make_shared( stateSpace, interpolator, dmetric, sampler, boundsConstraint, boundsProjection); diff --git a/aikido/tests/planner/ompl/test_OMPLGoalSets.cpp b/aikido/tests/planner/ompl/test_OMPLGoalSets.cpp index a4576c6c3d..ac846d626c 100644 --- a/aikido/tests/planner/ompl/test_OMPLGoalSets.cpp +++ b/aikido/tests/planner/ompl/test_OMPLGoalSets.cpp @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/aikido/tests/planner/ompl/test_OMPLPlanner.cpp b/aikido/tests/planner/ompl/test_OMPLPlanner.cpp index dc61d694f4..d1b52b4296 100644 --- a/aikido/tests/planner/ompl/test_OMPLPlanner.cpp +++ b/aikido/tests/planner/ompl/test_OMPLPlanner.cpp @@ -1,6 +1,6 @@ #include "OMPLTestHelpers.hpp" #include "../../constraint/MockConstraints.hpp" -#include +#include #include #include #include @@ -11,7 +11,7 @@ using StateSpace = aikido::statespace::dart::MetaSkeletonStateSpace; using Rn = aikido::statespace::Rn; using aikido::planner::ompl::getSpaceInformation; -TEST_F(OMPLPlannerTest, PlanToConfiguration) +TEST_F(PlannerTest, PlanToConfiguration) { Eigen::Vector3d startPose(-5, -5, 0); Eigen::Vector3d goalPose(5, 5, 0); @@ -44,7 +44,7 @@ TEST_F(OMPLPlannerTest, PlanToConfiguration) EXPECT_TRUE(r0.getValue().isApprox(goalPose)); } -TEST_F(OMPLPlannerTest, PlanToGoalRegion) +TEST_F(PlannerTest, PlanToGoalRegion) { auto startState = stateSpace->createState(); Eigen::Vector3d startPose(-5, -5, 0); @@ -87,7 +87,7 @@ TEST_F(OMPLPlannerTest, PlanToGoalRegion) EXPECT_TRUE(goalTestable->isSatisfied(s0)); } -TEST_F(OMPLPlannerTest, PlanThrowsOnNullGoalTestable) +TEST_F(PlannerTest, PlanThrowsOnNullGoalTestable) { auto startState = stateSpace->createState(); Eigen::Vector3d startPose(-5, -5, 0); @@ -109,7 +109,7 @@ TEST_F(OMPLPlannerTest, PlanThrowsOnNullGoalTestable) std::invalid_argument); } -TEST_F(OMPLPlannerTest, PlanThrowsOnGoalTestableMismatch) +TEST_F(PlannerTest, PlanThrowsOnGoalTestableMismatch) { auto startState = stateSpace->createState(); Eigen::Vector3d startPose(-5, -5, 0); @@ -136,7 +136,7 @@ TEST_F(OMPLPlannerTest, PlanThrowsOnGoalTestableMismatch) std::invalid_argument); } -TEST_F(OMPLPlannerTest, PlanThrowsOnNullGoalSampler) +TEST_F(PlannerTest, PlanThrowsOnNullGoalSampler) { auto startState = stateSpace->createState(); Eigen::Vector3d startPose(-5, -5, 0); @@ -157,7 +157,7 @@ TEST_F(OMPLPlannerTest, PlanThrowsOnNullGoalSampler) std::invalid_argument); } -TEST_F(OMPLPlannerTest, PlanThrowsOnGoalSamplerMismatch) +TEST_F(PlannerTest, PlanThrowsOnGoalSamplerMismatch) { auto startState = stateSpace->createState(); Eigen::Vector3d startPose(-5, -5, 0); @@ -184,7 +184,7 @@ TEST_F(OMPLPlannerTest, PlanThrowsOnGoalSamplerMismatch) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullStateSpace) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnNullStateSpace) { EXPECT_THROW(getSpaceInformation( nullptr, std::move(interpolator), std::move(dmetric), @@ -193,7 +193,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullStateSpace) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullInterpolator) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnNullInterpolator) { EXPECT_THROW(getSpaceInformation( std::move(stateSpace), nullptr, std::move(dmetric), @@ -202,7 +202,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullInterpolator) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnInterpolatorMismatch) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnInterpolatorMismatch) { auto ss = std::make_shared(); auto binterpolator = @@ -216,7 +216,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnInterpolatorMismatch) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullDistanceMetric) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnNullDistanceMetric) { EXPECT_THROW(getSpaceInformation( std::move(stateSpace), std::move(interpolator), nullptr, @@ -225,7 +225,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullDistanceMetric) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnDistanceMetricMismatch) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnDistanceMetricMismatch) { auto ss = std::make_shared(robot); auto dm = aikido::distance::createDistanceMetric(ss); @@ -237,7 +237,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnDistanceMetricMismatch) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullSampler) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnNullSampler) { EXPECT_THROW(getSpaceInformation( std::move(stateSpace), std::move(interpolator), @@ -246,7 +246,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullSampler) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnSamplerMismatch) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnSamplerMismatch) { auto ss = std::make_shared(robot); auto ds = aikido::constraint::createSampleableBounds(ss, make_rng()); @@ -258,7 +258,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnSamplerMismatch) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullValidityConstraint) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnNullValidityConstraint) { EXPECT_THROW(getSpaceInformation( std::move(stateSpace), std::move(interpolator), @@ -267,7 +267,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullValidityConstraint) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnValidityConstraintMismatch) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnValidityConstraintMismatch) { auto ss = std::make_shared(robot); auto dv = std::make_shared( @@ -279,7 +279,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnValidityConstraintMismatch) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullBoundsConstraint) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnNullBoundsConstraint) { EXPECT_THROW( getSpaceInformation(std::move(stateSpace), std::move(interpolator), @@ -289,7 +289,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullBoundsConstraint) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnBoundsConstraintMismatch) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnBoundsConstraintMismatch) { auto ss = std::make_shared(robot); auto ds = aikido::constraint::createTestableBounds(ss); @@ -302,7 +302,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnBoundsConstraintMismatch) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullBoundsProjector) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnNullBoundsProjector) { EXPECT_THROW( getSpaceInformation(std::move(stateSpace), std::move(interpolator), @@ -312,7 +312,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullBoundsProjector) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnBoundsProjectorMismatch) +TEST_F(PlannerTest, GetSpaceInformationThrowsOnBoundsProjectorMismatch) { auto ss = std::make_shared(robot); auto ds = aikido::constraint::createProjectableBounds(ss); @@ -325,7 +325,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnBoundsProjectorMismatch) std::invalid_argument); } -TEST_F(OMPLPlannerTest, GetSpaceInformationNotNull) +TEST_F(PlannerTest, GetSpaceInformationNotNull) { auto si = getSpaceInformation( std::move(stateSpace), std::move(interpolator), std::move(dmetric), @@ -334,7 +334,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationNotNull) EXPECT_FALSE(si == nullptr); } -TEST_F(OMPLPlannerTest, GetSpaceInformationCreatesGeometricStateSpace) +TEST_F(PlannerTest, GetSpaceInformationCreatesGeometricStateSpace) { auto si = getSpaceInformation( std::move(stateSpace), std::move(interpolator), std::move(dmetric), @@ -346,7 +346,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationCreatesGeometricStateSpace) EXPECT_FALSE(ss == nullptr); } -TEST_F(OMPLPlannerTest, GetSpaceInformationCreatesValidityChecker) +TEST_F(PlannerTest, GetSpaceInformationCreatesValidityChecker) { auto si = getSpaceInformation( std::move(stateSpace), std::move(interpolator), std::move(dmetric), diff --git a/aikido/tests/planner/ompl/test_StateSampler.cpp b/aikido/tests/planner/ompl/test_StateSampler.cpp index 3757368cae..244e958f16 100644 --- a/aikido/tests/planner/ompl/test_StateSampler.cpp +++ b/aikido/tests/planner/ompl/test_StateSampler.cpp @@ -5,12 +5,12 @@ using aikido::planner::ompl::GeometricStateSpace; using aikido::planner::ompl::StateSampler; using StateSpace = aikido::statespace::dart::MetaSkeletonStateSpace; -class StateSamplerTest : public OMPLPlannerTest +class StateSamplerTest : public PlannerTest { public: virtual void SetUp() { - OMPLPlannerTest::SetUp(); + PlannerTest::SetUp(); gSpace = std::make_shared( stateSpace, interpolator, dmetric, sampler, boundsConstraint, boundsProjection); diff --git a/aikido/tests/planner/ompl/test_ValidityChecker.cpp b/aikido/tests/planner/ompl/test_ValidityChecker.cpp index 4a17bf0d4d..9a66cd6173 100644 --- a/aikido/tests/planner/ompl/test_ValidityChecker.cpp +++ b/aikido/tests/planner/ompl/test_ValidityChecker.cpp @@ -1,18 +1,18 @@ #include "OMPLTestHelpers.hpp" #include "../../constraint/MockConstraints.hpp" #include -#include +#include using aikido::planner::ompl::GeometricStateSpace; using aikido::planner::ompl::StateValidityChecker; using StateSpace = aikido::statespace::dart::MetaSkeletonStateSpace; -class StateValidityCheckerTest : public OMPLPlannerTest +class StateValidityCheckerTest : public PlannerTest { public: virtual void SetUp() { - OMPLPlannerTest::SetUp(); + PlannerTest::SetUp(); gSpace = std::make_shared( stateSpace, interpolator, dmetric, sampler, boundsConstraint, boundsProjection);