Skip to content

Commit

Permalink
Renamed OMPLPlanner -> Planner.
Browse files Browse the repository at this point in the history
  • Loading branch information
Michael Koval committed Apr 22, 2016
1 parent 1defc27 commit 15eb6c9
Show file tree
Hide file tree
Showing 11 changed files with 37 additions and 37 deletions.
Expand Up @@ -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
2 changes: 1 addition & 1 deletion 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
)
Expand Down
@@ -1,4 +1,4 @@
#include <aikido/planner/ompl/OMPLPlanner.hpp>
#include <aikido/planner/ompl/Planner.hpp>
#include <aikido/planner/ompl/GeometricStateSpace.hpp>
#include <aikido/constraint/ConjunctionConstraint.hpp>

Expand Down
2 changes: 1 addition & 1 deletion aikido/tests/planner/ompl/OMPLTestHelpers.hpp
Expand Up @@ -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()
Expand Down
2 changes: 1 addition & 1 deletion aikido/tests/planner/ompl/test_GeometricStateSpace.cpp
Expand Up @@ -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()
Expand Down
6 changes: 3 additions & 3 deletions aikido/tests/planner/ompl/test_GoalRegion.cpp
@@ -1,18 +1,18 @@
#include "OMPLTestHelpers.hpp"
#include "../../constraint/MockConstraints.hpp"
#include <aikido/planner/ompl/GoalRegion.hpp>
#include <aikido/planner/ompl/OMPLPlanner.hpp>
#include <aikido/planner/ompl/Planner.hpp>

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<GeometricStateSpace>(
stateSpace, interpolator, dmetric, sampler, boundsConstraint,
boundsProjection);
Expand Down
2 changes: 1 addition & 1 deletion aikido/tests/planner/ompl/test_OMPLGoalSets.cpp
Expand Up @@ -10,7 +10,7 @@
#include <aikido/distance/Defaults.hpp>
#include <aikido/statespace/dart/MetaSkeletonStateSpace.hpp>
#include <aikido/statespace/GeodesicInterpolator.hpp>
#include <aikido/planner/ompl/OMPLPlanner.hpp>
#include <aikido/planner/ompl/Planner.hpp>
#include <aikido/util/RNG.hpp>
#include <dart/dart.h>
#include <gtest/gtest.h>
Expand Down
46 changes: 23 additions & 23 deletions aikido/tests/planner/ompl/test_OMPLPlanner.cpp
@@ -1,6 +1,6 @@
#include "OMPLTestHelpers.hpp"
#include "../../constraint/MockConstraints.hpp"
#include <aikido/planner/ompl/OMPLPlanner.hpp>
#include <aikido/planner/ompl/Planner.hpp>
#include <aikido/constraint/uniform/RealVectorBoxConstraint.hpp>
#include <aikido/constraint/SampleableSubSpace.h>
#include <aikido/constraint/TestableSubSpace.hpp>
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand All @@ -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);
Expand All @@ -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);
Expand All @@ -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),
Expand All @@ -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),
Expand All @@ -202,7 +202,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullInterpolator)
std::invalid_argument);
}

TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnInterpolatorMismatch)
TEST_F(PlannerTest, GetSpaceInformationThrowsOnInterpolatorMismatch)
{
auto ss = std::make_shared<aikido::statespace::SO2>();
auto binterpolator =
Expand All @@ -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,
Expand All @@ -225,7 +225,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullDistanceMetric)
std::invalid_argument);
}

TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnDistanceMetricMismatch)
TEST_F(PlannerTest, GetSpaceInformationThrowsOnDistanceMetricMismatch)
{
auto ss = std::make_shared<StateSpace>(robot);
auto dm = aikido::distance::createDistanceMetric(ss);
Expand All @@ -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),
Expand All @@ -246,7 +246,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullSampler)
std::invalid_argument);
}

TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnSamplerMismatch)
TEST_F(PlannerTest, GetSpaceInformationThrowsOnSamplerMismatch)
{
auto ss = std::make_shared<StateSpace>(robot);
auto ds = aikido::constraint::createSampleableBounds(ss, make_rng());
Expand All @@ -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),
Expand All @@ -267,7 +267,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullValidityConstraint)
std::invalid_argument);
}

TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnValidityConstraintMismatch)
TEST_F(PlannerTest, GetSpaceInformationThrowsOnValidityConstraintMismatch)
{
auto ss = std::make_shared<StateSpace>(robot);
auto dv = std::make_shared<MockTranslationalRobotConstraint>(
Expand All @@ -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),
Expand All @@ -289,7 +289,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullBoundsConstraint)
std::invalid_argument);
}

TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnBoundsConstraintMismatch)
TEST_F(PlannerTest, GetSpaceInformationThrowsOnBoundsConstraintMismatch)
{
auto ss = std::make_shared<StateSpace>(robot);
auto ds = aikido::constraint::createTestableBounds(ss);
Expand All @@ -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),
Expand All @@ -312,7 +312,7 @@ TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnNullBoundsProjector)
std::invalid_argument);
}

TEST_F(OMPLPlannerTest, GetSpaceInformationThrowsOnBoundsProjectorMismatch)
TEST_F(PlannerTest, GetSpaceInformationThrowsOnBoundsProjectorMismatch)
{
auto ss = std::make_shared<StateSpace>(robot);
auto ds = aikido::constraint::createProjectableBounds(ss);
Expand All @@ -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),
Expand All @@ -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),
Expand All @@ -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),
Expand Down
4 changes: 2 additions & 2 deletions aikido/tests/planner/ompl/test_StateSampler.cpp
Expand Up @@ -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<GeometricStateSpace>(
stateSpace, interpolator, dmetric, sampler, boundsConstraint,
boundsProjection);
Expand Down
6 changes: 3 additions & 3 deletions aikido/tests/planner/ompl/test_ValidityChecker.cpp
@@ -1,18 +1,18 @@
#include "OMPLTestHelpers.hpp"
#include "../../constraint/MockConstraints.hpp"
#include <aikido/planner/ompl/StateValidityChecker.hpp>
#include <aikido/planner/ompl/OMPLPlanner.hpp>
#include <aikido/planner/ompl/Planner.hpp>

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<GeometricStateSpace>(
stateSpace, interpolator, dmetric, sampler, boundsConstraint,
boundsProjection);
Expand Down

0 comments on commit 15eb6c9

Please sign in to comment.