Skip to content

Commit

Permalink
Renaming ProjectableSubSpace to CartesianProductProjectable
Browse files Browse the repository at this point in the history
  • Loading branch information
jeking04 committed Apr 22, 2016
1 parent bb77b7e commit 206604b
Show file tree
Hide file tree
Showing 29 changed files with 89 additions and 89 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#ifndef AIKIDO_CONSTRAINT_PROJECTABLESUBSPACE_H_
#define AIKIDO_CONSTRAINT_PROJECTABLESUBSPACE_H_
#ifndef AIKIDO_CONSTRAINT_CARTESIANPRODUCTPROJECTABLE_HPP_
#define AIKIDO_CONSTRAINT_CARTESIANPRODUCTPROJECTABLE_HPP_
#include "Projectable.hpp"
#include "../statespace/CartesianProduct.hpp"

Expand All @@ -9,7 +9,7 @@ namespace constraint {
/// A Projectable for CompoundStates.
/// It takes in a set of Projectables and project
/// i-th substate to i-th constraint.
class ProjectableSubSpace : public Projectable
class CartesianProductProjectable : public Projectable
{
public:

Expand All @@ -18,7 +18,7 @@ class ProjectableSubSpace : public Projectable
/// \param _constraints Set of constraints. The size of _constraints
/// should match the number of subspaces in _stateSpace.
/// i-th constraint applies to i-th subspace.
ProjectableSubSpace(
CartesianProductProjectable(
std::shared_ptr<statespace::CartesianProduct> _stateSpace,
std::vector<ProjectablePtr> _constraints);

Expand All @@ -39,4 +39,4 @@ class ProjectableSubSpace : public Projectable
} // namespace constraint
} // namespace aikido

#endif // ifndef AIKIDO_CONSTRAINT_PROJECTABLESUBSPACE_HPP_
#endif // ifndef AIKIDO_CONSTRAINT_CARTESIANPRODUCTPROJECTABLE_HPP_
6 changes: 3 additions & 3 deletions aikido/include/aikido/constraint/CyclicSampleable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@ namespace constraint {
/// the original sampleable constraint, but once the samples are exhausted,
/// it will cycle through the samples, starting from the initial sample.
/// The original sampleable should be finite.
class CyclicSampleable : public SampleableConstraint
class CyclicSampleable : public Sampleable
{
public:

/// Constructor.
/// \param _sampleable Sampleable whose samples are to be iterated.
explicit CyclicSampleable(
SampleableConstraintPtr _sampleable);
SampleablePtr _sampleable);

/// Documentation inherited.
statespace::StateSpacePtr getStateSpace() const override;
Expand All @@ -28,7 +28,7 @@ class CyclicSampleable : public SampleableConstraint
std::unique_ptr<SampleGenerator> createSampleGenerator() const override;

private:
SampleableConstraintPtr mSampleable;
SampleablePtr mSampleable;
statespace::StateSpacePtr mStateSpace;

};
Expand Down
2 changes: 1 addition & 1 deletion aikido/include/aikido/constraint/FiniteSampleable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ namespace constraint {
/// Constraint that always returns a finite set of samples.
/// Its SampleGenerator will generate sample
/// until all samples are exhausted.
class FiniteSampleable : public SampleableConstraint
class FiniteSampleable : public Sampleable
{
public:
/// Constructor for single-sample constraint.
Expand Down
10 changes: 5 additions & 5 deletions aikido/include/aikido/constraint/InverseKinematicsSampleable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ namespace constraint {
/// into the metaskeleton's configuration space. This class will retry a
/// configurable number of times if sampling from the provided sampleable
/// pose constraint or finding an inverse kinematic solution fails.
class InverseKinematicsSampleable : public SampleableConstraint
class InverseKinematicsSampleable : public Sampleable
{
public:

Expand All @@ -31,8 +31,8 @@ class InverseKinematicsSampleable : public SampleableConstraint
/// to retry sampling and finding an inverse kinematics solution.
InverseKinematicsSampleable(
statespace::dart::MetaSkeletonStateSpacePtr _stateSpace,
SampleableConstraintPtr _poseConstraint,
SampleableConstraintPtr _seedConstraint,
SampleablePtr _poseConstraint,
SampleablePtr _seedConstraint,
dart::dynamics::InverseKinematicsPtr _inverseKinematics,
int _maxNumTrials);

Expand All @@ -47,8 +47,8 @@ class InverseKinematicsSampleable : public SampleableConstraint

private:
statespace::dart::MetaSkeletonStateSpacePtr mStateSpace;
SampleableConstraintPtr mPoseConstraint;
SampleableConstraintPtr mSeedConstraint;
SampleablePtr mPoseConstraint;
SampleablePtr mSeedConstraint;
dart::dynamics::InverseKinematicsPtr mInverseKinematics;
int mMaxNumTrials;
};
Expand Down
10 changes: 5 additions & 5 deletions aikido/include/aikido/constraint/Sampleable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,9 @@ class SampleGenerator;
/// samples. For that reason, you should be careful to use the same
/// SampleGenerator when obtaining a sequence of samples to avoid
/// re-sampling the beginning of the same deterministic sequence repeatedly.
class SampleableConstraint {
class Sampleable {
public:
virtual ~SampleableConstraint() = default;
virtual ~Sampleable() = default;

/// Gets the StateSpace that this constraint operates on.
virtual statespace::StateSpacePtr getStateSpace() const = 0;
Expand All @@ -32,7 +32,7 @@ class SampleableConstraint {
};


/// Generator for drawing samples from a SampleableConstraint. This object
/// Generator for drawing samples from a Sampleable. This object
/// may represent both finite and inifinite sets of samples, as indicated by
/// the return value of getNumSamples(). Note that this value provides only an
/// upper bound on the number of samples available: sample() may transiently
Expand All @@ -57,10 +57,10 @@ class SampleGenerator {
virtual bool canSample() const = 0;
};

using SampleableConstraintPtr = std::shared_ptr<SampleableConstraint>;
using SampleablePtr = std::shared_ptr<Sampleable>;


} // namespace constraint
} // namespace aikido

#endif // AIKIDO_CONSTRAINT_SAMPLEABLE_H_
#endif // AIKIDO_CONSTRAINT_SAMPLEABLE_HPP_
6 changes: 3 additions & 3 deletions aikido/include/aikido/constraint/SampleableSubSpace.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ namespace constraint {
/// Sampleable for CompoundStates.
/// It takes in a set of Sampleables and its SampleGenerators
/// sample i-th substate from the i-th Sampleable.
class SampleableSubSpace : public SampleableConstraint
class SampleableSubSpace : public Sampleable
{
public:

Expand All @@ -21,7 +21,7 @@ class SampleableSubSpace : public SampleableConstraint
/// i-th constraint applies to i-th subspace.
SampleableSubSpace(
std::shared_ptr<statespace::CartesianProduct> _stateSpace,
std::vector<std::shared_ptr<SampleableConstraint>> _constraints);
std::vector<std::shared_ptr<Sampleable>> _constraints);

// Documentation inherited.
statespace::StateSpacePtr getStateSpace() const override;
Expand All @@ -31,7 +31,7 @@ class SampleableSubSpace : public SampleableConstraint

private:
std::shared_ptr<statespace::CartesianProduct> mStateSpace;
std::vector<std::shared_ptr<SampleableConstraint>> mConstraints;
std::vector<std::shared_ptr<Sampleable>> mConstraints;
};

} // namespace constraint
Expand Down
2 changes: 1 addition & 1 deletion aikido/include/aikido/constraint/TSR.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ namespace constraint {
/// "Task space regions: A framework for pose-constrained manipulation
/// planning." IJRR 2001:
/// http://repository.cmu.edu/cgi/viewcontent.cgi?article=2024&context=robotics
class TSR : public SampleableConstraint,
class TSR : public Sampleable,
public Differentiable,
public Testable,
public Projectable
Expand Down
6 changes: 3 additions & 3 deletions aikido/include/aikido/constraint/dart.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ std::unique_ptr<Testable> createTestableBounds(
/// \param _stateSpace The StateSpace where the Sampleable will be applied.
/// \param _rng The random number generator to be used by the Sampleable
template <class Space>
std::unique_ptr<SampleableConstraint> createSampleableBoundsFor(
std::unique_ptr<Sampleable> createSampleableBoundsFor(
std::shared_ptr<Space> _stateSpace, std::unique_ptr<util::RNG> _rng);

/// Create a Sampleabe constraint that can be used to sample values for the
Expand All @@ -91,7 +91,7 @@ std::unique_ptr<SampleableConstraint> createSampleableBoundsFor(
/// JointStateSpace.
/// \param _stateSpace The JointStateSpace where the Sampleable will be applied
/// \param _rng The random number generator to be used by the Sampleable
std::unique_ptr<SampleableConstraint> createSampleableBounds(
std::unique_ptr<Sampleable> createSampleableBounds(
std::shared_ptr<statespace::dart::JointStateSpace> _stateSpace,
std::unique_ptr<util::RNG> _rng);

Expand All @@ -101,7 +101,7 @@ std::unique_ptr<SampleableConstraint> createSampleableBounds(
/// \param _metaSkeleton The MetaSkeletonStateSpace where the Sampleable will be
/// applied
/// \param _rng The random number generator to be used by the Sampleable
std::unique_ptr<SampleableConstraint> createSampleableBounds(
std::unique_ptr<Sampleable> createSampleableBounds(
statespace::dart::MetaSkeletonStateSpacePtr _metaSkeleton,
std::unique_ptr<util::RNG> _rng);

Expand Down
14 changes: 7 additions & 7 deletions aikido/include/aikido/constraint/detail/dart.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ struct createSampleableFor_impl<statespace::dart::RnJoint>
using StateSpace = statespace::dart::RnJoint;
using StateSpacePtr = std::shared_ptr<StateSpace>;

static std::unique_ptr<SampleableConstraint> create(
static std::unique_ptr<Sampleable> create(
StateSpacePtr _stateSpace, std::unique_ptr<util::RNG> _rng)
{
const auto joint = _stateSpace->getJoint();
Expand Down Expand Up @@ -202,14 +202,14 @@ struct createSampleableFor_impl<statespace::dart::SO2Joint>
using StateSpace = statespace::dart::SO2Joint;
using StateSpacePtr = std::shared_ptr<StateSpace>;

static std::unique_ptr<SampleableConstraint> create(
static std::unique_ptr<Sampleable> create(
StateSpacePtr _stateSpace, std::unique_ptr<util::RNG> _rng)
{
if (isLimited(_stateSpace->getJoint()))
throw std::invalid_argument("SO2Joint must not have limits.");

return dart::common::make_unique<
statespace::SO2SampleableConstraint>(
statespace::SO2Sampleable>(
std::move(_stateSpace), std::move(_rng));
}
};
Expand Down Expand Up @@ -269,7 +269,7 @@ struct createSampleableFor_impl<statespace::dart::SO3Joint>
using StateSpace = statespace::dart::SO3Joint;
using StateSpacePtr = std::shared_ptr<StateSpace>;

static std::unique_ptr<SampleableConstraint> create(
static std::unique_ptr<Sampleable> create(
StateSpacePtr _stateSpace, std::unique_ptr<util::RNG> _rng)
{
if (isLimited(_stateSpace->getJoint()))
Expand Down Expand Up @@ -326,7 +326,7 @@ struct createSampleableFor_impl<statespace::dart::SE2Joint>
using StateSpace = statespace::dart::SE2Joint;
using StateSpacePtr = std::shared_ptr<StateSpace>;

static std::unique_ptr<SampleableConstraint> create(
static std::unique_ptr<Sampleable> create(
StateSpacePtr _stateSpace, std::unique_ptr<util::RNG> _rng)
{
throw std::runtime_error(
Expand Down Expand Up @@ -380,7 +380,7 @@ struct createSampleableFor_impl<statespace::dart::SE3Joint>
using StateSpace = statespace::dart::SE3Joint;
using StateSpacePtr = std::shared_ptr<StateSpace>;

static std::unique_ptr<SampleableConstraint> create(
static std::unique_ptr<Sampleable> create(
StateSpacePtr _stateSpace, std::unique_ptr<util::RNG> _rng)
{
throw std::runtime_error(
Expand Down Expand Up @@ -419,7 +419,7 @@ std::unique_ptr<Testable> createTestableBoundsFor(

//=============================================================================
template <class Space>
std::unique_ptr<SampleableConstraint> createSampleableBoundsFor(
std::unique_ptr<Sampleable> createSampleableBoundsFor(
std::shared_ptr<Space> _stateSpace, std::unique_ptr<util::RNG> _rng)
{
return detail::createSampleableFor_impl<Space>::create(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ namespace statespace {
class RealVectorBoxConstraint
: public constraint::Differentiable
, public constraint::Projectable
, public constraint::SampleableConstraint
, public constraint::Sampleable
, public constraint::Testable
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,15 +9,15 @@ namespace statespace {
/// Uniform sampler for SO2States. Its SampleGenerators will sample
/// uniformly from SO2, and the sequence of samples is
/// deterministically generated given a random number generator seed.
class SO2SampleableConstraint
: public constraint::SampleableConstraint
class SO2Sampleable
: public constraint::Sampleable
{
public:
/// Constructor.
/// \param _space SO2 in which this constraint operates.
/// \param _rng Random number generator which determines the sampling
/// sequence of this constraint's SampleGenerators.
SO2SampleableConstraint(
SO2Sampleable(
std::shared_ptr<statespace::SO2> _space,
std::unique_ptr<util::RNG> _rng);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ namespace statespace {
/// Uniform sampler for SO3States. Its SampleGenerators will sample
/// uniformly from SO3, and the sequence of samples is
/// deterministically generated given a random number generator seed.
class SO3UniformSampler : public constraint::SampleableConstraint
class SO3UniformSampler : public constraint::Sampleable
{
public:

Expand Down
4 changes: 2 additions & 2 deletions aikido/include/aikido/ompl/AIKIDOGeometricStateSpace.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class GeometricStateSpace : public ::ompl::base::StateSpace
GeometricStateSpace(statespace::StateSpacePtr _sspace,
statespace::InterpolatorPtr _interpolator,
distance::DistanceMetricPtr _dmetric,
constraint::SampleableConstraintPtr _sampler,
constraint::SampleablePtr _sampler,
constraint::TestablePtr _boundsConstraint,
constraint::ProjectablePtr _boundsProjection);

Expand Down Expand Up @@ -117,7 +117,7 @@ class GeometricStateSpace : public ::ompl::base::StateSpace
statespace::StateSpacePtr mStateSpace;
statespace::InterpolatorPtr mInterpolator;
distance::DistanceMetricPtr mDistance;
constraint::SampleableConstraintPtr mSampler;
constraint::SampleablePtr mSampler;
constraint::TestablePtr mBoundsConstraint;
constraint::ProjectablePtr mBoundsProjection;
};
Expand Down
14 changes: 7 additions & 7 deletions aikido/include/aikido/ompl/OMPLPlanner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ namespace ompl {
/// \param _interpolator An Interpolator defined on the StateSpace. This is used
/// to interpolate between two points within the space.
/// \param _dmetric A valid distance metric defined on the StateSpace
/// \param _sampler A SampleableConstraint that can sample states from the
/// \param _sampler A Sampleable that can sample states from the
/// StateSpace. Warning: Many OMPL planners internally assume this sampler
/// samples uniformly. Care should be taken when using a non-uniform sampler.
/// \param _validityConstraint A constraint used to test validity during
Expand All @@ -45,7 +45,7 @@ trajectory::TrajectoryPtr planOMPL(
statespace::StateSpacePtr _stateSpace,
statespace::InterpolatorPtr _interpolator,
distance::DistanceMetricPtr _dmetric,
constraint::SampleableConstraintPtr _sampler,
constraint::SampleablePtr _sampler,
constraint::TestablePtr _validityConstraint,
constraint::TestablePtr _boundsConstraint,
constraint::ProjectablePtr _boundsProjector, double _maxPlanTime);
Expand All @@ -59,7 +59,7 @@ trajectory::TrajectoryPtr planOMPL(
/// \param _interpolator An Interpolator defined on the StateSpace. This is used
/// to interpolate between two points within the space.
/// \param _dmetric A valid distance metric defined on the StateSpace
/// \param _sampler A SampleableConstraint that can sample states from the
/// \param _sampler A Sampleable that can sample states from the
/// StateSpace. Warning: Many OMPL planners internally assume this sampler
/// samples uniformly. Care should be taken when using a non-uniform sampler.
/// \param _validityConstraint A constraint used to test validity during
Expand All @@ -77,11 +77,11 @@ template <class PlannerType>
trajectory::TrajectoryPtr planOMPL(
const statespace::StateSpace::State *_start,
constraint::TestablePtr _goalTestable,
constraint::SampleableConstraintPtr _goalSampler,
constraint::SampleablePtr _goalSampler,
statespace::StateSpacePtr _stateSpace,
statespace::InterpolatorPtr _interpolator,
distance::DistanceMetricPtr _dmetric,
constraint::SampleableConstraintPtr _sampler,
constraint::SampleablePtr _sampler,
constraint::TestablePtr _validityConstraint,
constraint::TestablePtr _boundsConstraint,
constraint::ProjectablePtr _boundsProjector,
Expand All @@ -92,7 +92,7 @@ trajectory::TrajectoryPtr planOMPL(
/// \param _interpolator An Interpolator defined on the StateSpace. This is used
/// to interpolate between two points within the space.
/// \param _dmetric A valid distance metric defined on the StateSpace
/// \param _sampler A SampleableConstraint that can sample states from the
/// \param _sampler A Sampleable that can sample states from the
/// StateSpace. Warning: Many OMPL planners internally assume this sampler
/// samples uniformly. Care should be taken when using a non-uniform sampler.
/// \param _validityConstraint A constraint used to test validity during
Expand All @@ -108,7 +108,7 @@ ::ompl::base::SpaceInformationPtr getSpaceInformation(
statespace::StateSpacePtr _stateSpace,
statespace::InterpolatorPtr _interpolator,
distance::DistanceMetricPtr _dmetric,
constraint::SampleableConstraintPtr _sampler,
constraint::SampleablePtr _sampler,
constraint::TestablePtr _validityConstraint,
constraint::TestablePtr _boundsConstraint,
constraint::ProjectablePtr _boundsProjector);
Expand Down
6 changes: 3 additions & 3 deletions aikido/include/aikido/ompl/detail/OMPLPlanner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ trajectory::TrajectoryPtr planOMPL(
statespace::StateSpacePtr _stateSpace,
statespace::InterpolatorPtr _interpolator,
distance::DistanceMetricPtr _dmetric,
constraint::SampleableConstraintPtr _sampler,
constraint::SampleablePtr _sampler,
constraint::TestablePtr _validityConstraint,
constraint::TestablePtr _boundsConstraint,
constraint::ProjectablePtr _boundsProjector, double _maxPlanTime)
Expand Down Expand Up @@ -49,11 +49,11 @@ template <class PlannerType>
trajectory::TrajectoryPtr planOMPL(
const statespace::StateSpace::State *_start,
constraint::TestablePtr _goalTestable,
constraint::SampleableConstraintPtr _goalSampler,
constraint::SampleablePtr _goalSampler,
statespace::StateSpacePtr _stateSpace,
statespace::InterpolatorPtr _interpolator,
distance::DistanceMetricPtr _dmetric,
constraint::SampleableConstraintPtr _sampler,
constraint::SampleablePtr _sampler,
constraint::TestablePtr _validityConstraint,
constraint::TestablePtr _boundsConstraint,
constraint::ProjectablePtr _boundsProjector,
Expand Down
Loading

0 comments on commit 206604b

Please sign in to comment.