Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix compiling dart::common::make_unique() with recent GCC versions #481

Merged
merged 4 commits into from
Jan 17, 2019
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,6 @@ namespace constraint {
namespace dart {
namespace detail {

using ::dart::common::make_unique;

//==============================================================================
using JointStateSpaceTypeList
= common::type_list<const statespace::dart::R0Joint,
Expand Down Expand Up @@ -69,15 +67,15 @@ std::unique_ptr<OutputConstraint> createBoxConstraint(

if (properties.isPositionLimited())
{
return make_unique<uniform::RBoxConstraint<N>>(
return ::dart::common::make_unique<uniform::RBoxConstraint<N>>(
std::move(_stateSpace),
std::move(_rng),
properties.getPositionLowerLimits(),
properties.getPositionUpperLimits());
}
else
{
return make_unique<Satisfied>(std::move(_stateSpace));
return ::dart::common::make_unique<Satisfied>(std::move(_stateSpace));
}
}

Expand Down Expand Up @@ -135,7 +133,7 @@ struct createSampleableFor_impl<const statespace::dart::RJoint<N>>

if (properties.isPositionLimited())
{
return make_unique<uniform::RBoxConstraint<N>>(
return ::dart::common::make_unique<uniform::RBoxConstraint<N>>(
std::move(_stateSpace),
std::move(_rng),
properties.getPositionLowerLimits(),
Expand All @@ -160,7 +158,7 @@ struct createDifferentiableFor_impl<const statespace::dart::SO2Joint>
if (_stateSpace->getProperties().isPositionLimited())
throw std::invalid_argument("SO2Joint must not have limits.");

return make_unique<Satisfied>(std::move(_stateSpace));
return ::dart::common::make_unique<Satisfied>(std::move(_stateSpace));
}
};

Expand All @@ -176,7 +174,7 @@ struct createTestableFor_impl<const statespace::dart::SO2Joint>
if (_stateSpace->getProperties().isPositionLimited())
throw std::invalid_argument("SO2Joint must not have limits.");

return make_unique<Satisfied>(std::move(_stateSpace));
return ::dart::common::make_unique<Satisfied>(std::move(_stateSpace));
}
};

Expand All @@ -192,7 +190,7 @@ struct createProjectableFor_impl<const statespace::dart::SO2Joint>
if (_stateSpace->getProperties().isPositionLimited())
throw std::invalid_argument("SO2Joint must not have limits.");

return make_unique<Satisfied>(std::move(_stateSpace));
return ::dart::common::make_unique<Satisfied>(std::move(_stateSpace));
}
};

Expand All @@ -209,7 +207,7 @@ struct createSampleableFor_impl<const statespace::dart::SO2Joint>
if (_stateSpace->getProperties().isPositionLimited())
throw std::invalid_argument("SO2Joint must not have limits.");

return make_unique<uniform::SO2UniformSampler>(
return ::dart::common::make_unique<uniform::SO2UniformSampler>(
std::move(_stateSpace), std::move(_rng));
}
};
Expand All @@ -226,7 +224,7 @@ struct createDifferentiableFor_impl<const statespace::dart::SO3Joint>
if (_stateSpace->getProperties().isPositionLimited())
throw std::invalid_argument("SO3Joint must not have limits.");

return make_unique<Satisfied>(std::move(_stateSpace));
return ::dart::common::make_unique<Satisfied>(std::move(_stateSpace));
}
};

Expand All @@ -242,7 +240,7 @@ struct createTestableFor_impl<const statespace::dart::SO3Joint>
if (_stateSpace->getProperties().isPositionLimited())
throw std::invalid_argument("SO3Joint must not have limits.");

return make_unique<Satisfied>(std::move(_stateSpace));
return ::dart::common::make_unique<Satisfied>(std::move(_stateSpace));
}
};

Expand All @@ -258,7 +256,7 @@ struct createProjectableFor_impl<const statespace::dart::SO3Joint>
if (_stateSpace->getProperties().isPositionLimited())
throw std::invalid_argument("SO3Joint must not have limits.");

return make_unique<Satisfied>(std::move(_stateSpace));
return ::dart::common::make_unique<Satisfied>(std::move(_stateSpace));
}
};

Expand All @@ -275,7 +273,7 @@ struct createSampleableFor_impl<const statespace::dart::SO3Joint>
if (_stateSpace->getProperties().isPositionLimited())
throw std::invalid_argument("SO3Joint must not have limits.");

return make_unique<uniform::SO3UniformSampler>(
return ::dart::common::make_unique<uniform::SO3UniformSampler>(
std::move(_stateSpace), std::move(_rng));
}
};
Expand All @@ -290,15 +288,15 @@ std::unique_ptr<OutputConstraint> createBoxConstraint(

if (properties.isPositionLimited())
{
return make_unique<uniform::SE2BoxConstraint>(
return ::dart::common::make_unique<uniform::SE2BoxConstraint>(
std::move(_stateSpace),
std::move(_rng),
properties.getPositionLowerLimits().tail<2>(),
properties.getPositionUpperLimits().tail<2>());
}
else
{
return make_unique<Satisfied>(std::move(_stateSpace));
return ::dart::common::make_unique<Satisfied>(std::move(_stateSpace));
}
}

Expand Down Expand Up @@ -381,7 +379,7 @@ struct createSampleableFor_impl<const statespace::dart::SE2Joint>
}
else
{
return make_unique<uniform::SE2BoxConstraint>(
return ::dart::common::make_unique<uniform::SE2BoxConstraint>(
std::move(stateSpace),
std::move(rng),
properties.getPositionLowerLimits().tail<2>(),
Expand Down Expand Up @@ -451,7 +449,7 @@ std::unique_ptr<OutputConstraint> createBoxConstraint(
std::shared_ptr<const statespace::dart::WeldJoint> _stateSpace,
std::unique_ptr<common::RNG> /*_rng*/)
{
return make_unique<Satisfied>(std::move(_stateSpace));
return ::dart::common::make_unique<Satisfied>(std::move(_stateSpace));
}

//==============================================================================
Expand Down Expand Up @@ -506,7 +504,7 @@ struct createSampleableFor_impl<const statespace::dart::WeldJoint>
// A WeldJoint has zero DOFs
Eigen::VectorXd positions = Eigen::Matrix<double, 0, 1>();

return make_unique<uniform::R0ConstantSampler>(
return ::dart::common::make_unique<uniform::R0ConstantSampler>(
std::move(_stateSpace), positions);
}
};
Expand Down
19 changes: 9 additions & 10 deletions include/aikido/distance/detail/defaults-impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@ namespace aikido {
namespace distance {
namespace detail {

using dart::common::make_unique;
using Ptr = std::unique_ptr<DistanceMetric>;

//==============================================================================
Expand All @@ -32,7 +31,7 @@ struct createDistanceMetricFor_impl<const statespace::R0>
{
static Ptr create(std::shared_ptr<const statespace::R0> _sspace)
{
return make_unique<R0Euclidean>(std::move(_sspace));
return ::dart::common::make_unique<R0Euclidean>(std::move(_sspace));
}
};

Expand All @@ -42,7 +41,7 @@ struct createDistanceMetricFor_impl<const statespace::R1>
{
static Ptr create(std::shared_ptr<const statespace::R1> _sspace)
{
return make_unique<R1Euclidean>(std::move(_sspace));
return ::dart::common::make_unique<R1Euclidean>(std::move(_sspace));
}
};

Expand All @@ -52,7 +51,7 @@ struct createDistanceMetricFor_impl<const statespace::R2>
{
static Ptr create(std::shared_ptr<const statespace::R2> _sspace)
{
return make_unique<R2Euclidean>(std::move(_sspace));
return ::dart::common::make_unique<R2Euclidean>(std::move(_sspace));
}
};

Expand All @@ -62,7 +61,7 @@ struct createDistanceMetricFor_impl<const statespace::R3>
{
static Ptr create(std::shared_ptr<const statespace::R3> _sspace)
{
return make_unique<R3Euclidean>(std::move(_sspace));
return ::dart::common::make_unique<R3Euclidean>(std::move(_sspace));
}
};

Expand All @@ -72,7 +71,7 @@ struct createDistanceMetricFor_impl<const statespace::R6>
{
static Ptr create(std::shared_ptr<const statespace::R6> _sspace)
{
return make_unique<R6Euclidean>(std::move(_sspace));
return ::dart::common::make_unique<R6Euclidean>(std::move(_sspace));
}
};

Expand All @@ -82,7 +81,7 @@ struct createDistanceMetricFor_impl<const statespace::SO2>
{
static Ptr create(std::shared_ptr<const statespace::SO2> _sspace)
{
return make_unique<SO2Angular>(std::move(_sspace));
return ::dart::common::make_unique<SO2Angular>(std::move(_sspace));
}
};

Expand All @@ -92,7 +91,7 @@ struct createDistanceMetricFor_impl<const statespace::SO3>
{
static Ptr create(std::shared_ptr<const statespace::SO3> _sspace)
{
return make_unique<SO3Angular>(std::move(_sspace));
return ::dart::common::make_unique<SO3Angular>(std::move(_sspace));
}
};

Expand All @@ -116,7 +115,7 @@ struct createDistanceMetricFor_impl<const statespace::CartesianProduct>
metrics.emplace_back(std::move(metric));
}

return make_unique<CartesianProductWeighted>(
return ::dart::common::make_unique<CartesianProductWeighted>(
std::move(_sspace), std::move(metrics));
}
};
Expand All @@ -127,7 +126,7 @@ struct createDistanceMetricFor_impl<const statespace::SE2>
{
static Ptr create(std::shared_ptr<const statespace::SE2> _sspace)
{
return make_unique<SE2Weighted>(std::move(_sspace));
return ::dart::common::make_unique<SE2Weighted>(std::move(_sspace));
}
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@ namespace statespace {
namespace dart {
namespace detail {

using ::dart::common::make_unique;
using Ptr = std::unique_ptr<JointStateSpace>;

//==============================================================================
Expand All @@ -29,9 +28,9 @@ struct createJointStateSpaceFor_impl<const ::dart::dynamics::RevoluteJoint>
static Ptr create(const ::dart::dynamics::RevoluteJoint* _joint)
{
if (_joint->isCyclic(0))
return make_unique<SO2Joint>(_joint);
return ::dart::common::make_unique<SO2Joint>(_joint);
else
return make_unique<R1Joint>(_joint);
return ::dart::common::make_unique<R1Joint>(_joint);
}
};

Expand All @@ -41,7 +40,7 @@ struct createJointStateSpaceFor_impl<const ::dart::dynamics::PrismaticJoint>
{
static Ptr create(const ::dart::dynamics::PrismaticJoint* _joint)
{
return make_unique<R1Joint>(_joint);
return ::dart::common::make_unique<R1Joint>(_joint);
}
};

Expand All @@ -51,7 +50,7 @@ struct createJointStateSpaceFor_impl<const ::dart::dynamics::TranslationalJoint>
{
static Ptr create(const ::dart::dynamics::TranslationalJoint* _joint)
{
return make_unique<R3Joint>(_joint);
return ::dart::common::make_unique<R3Joint>(_joint);
}
};

Expand All @@ -61,7 +60,7 @@ struct createJointStateSpaceFor_impl<const ::dart::dynamics::BallJoint>
{
static Ptr create(const ::dart::dynamics::BallJoint* _joint)
{
return make_unique<SO3Joint>(_joint);
return ::dart::common::make_unique<SO3Joint>(_joint);
}
};

Expand All @@ -71,7 +70,7 @@ struct createJointStateSpaceFor_impl<const ::dart::dynamics::PlanarJoint>
{
static Ptr create(const ::dart::dynamics::PlanarJoint* _joint)
{
return make_unique<SE2Joint>(_joint);
return ::dart::common::make_unique<SE2Joint>(_joint);
}
};

Expand All @@ -81,7 +80,7 @@ struct createJointStateSpaceFor_impl<const ::dart::dynamics::FreeJoint>
{
static Ptr create(const ::dart::dynamics::FreeJoint* _joint)
{
return make_unique<SE3Joint>(_joint);
return ::dart::common::make_unique<SE3Joint>(_joint);
}
};

Expand All @@ -91,7 +90,7 @@ struct createJointStateSpaceFor_impl<const ::dart::dynamics::WeldJoint>
{
static Ptr create(const ::dart::dynamics::WeldJoint* _joint)
{
return make_unique<WeldJoint>(_joint);
return ::dart::common::make_unique<WeldJoint>(_joint);
}
};

Expand Down
4 changes: 1 addition & 3 deletions src/constraint/CartesianProductSampleable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@
namespace aikido {
namespace constraint {

using dart::common::make_unique;

//==============================================================================
class SubspaceSampleGenerator : public SampleGenerator
{
Expand Down Expand Up @@ -133,7 +131,7 @@ CartesianProductSampleable::createSampleGenerator() const
for (const auto& constraint : mConstraints)
generators.emplace_back(constraint->createSampleGenerator());

return make_unique<SubspaceSampleGenerator>(
return ::dart::common::make_unique<SubspaceSampleGenerator>(
mStateSpace, std::move(generators));
}

Expand Down
2 changes: 0 additions & 2 deletions src/constraint/CartesianProductTestable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@
namespace aikido {
namespace constraint {

using dart::common::make_unique;

//==============================================================================
CartesianProductTestable::CartesianProductTestable(
std::shared_ptr<const statespace::CartesianProduct> _stateSpace,
Expand Down
2 changes: 1 addition & 1 deletion src/constraint/CyclicSampleable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,7 @@ statespace::ConstStateSpacePtr CyclicSampleable::getStateSpace() const
//==============================================================================
std::unique_ptr<SampleGenerator> CyclicSampleable::createSampleGenerator() const
{
return dart::common::make_unique<FiniteCyclicSampleGenerator>(
return ::dart::common::make_unique<FiniteCyclicSampleGenerator>(
mSampleable->createSampleGenerator());
}

Expand Down
3 changes: 2 additions & 1 deletion src/constraint/FiniteSampleable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,8 @@ statespace::ConstStateSpacePtr FiniteSampleable::getStateSpace() const
//==============================================================================
std::unique_ptr<SampleGenerator> FiniteSampleable::createSampleGenerator() const
{
return dart::common::make_unique<FiniteSampleGenerator>(mStateSpace, mStates);
return ::dart::common::make_unique<FiniteSampleGenerator>(
mStateSpace, mStates);
}

} // namespace constraint
Expand Down
4 changes: 1 addition & 3 deletions src/constraint/RejectionSampleable.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
#include <dart/common/StlHelpers.hpp>
#include <aikido/constraint/RejectionSampleable.hpp>

using dart::common::make_unique;

namespace aikido {
namespace constraint {

Expand Down Expand Up @@ -94,7 +92,7 @@ std::unique_ptr<SampleGenerator> RejectionSampleable::createSampleGenerator()
const
{
auto sampler = mSampleable->createSampleGenerator();
return make_unique<RejectionSampler>(
return ::dart::common::make_unique<RejectionSampler>(
mStateSpace, std::move(sampler), mTestable, mMaxTrialPerSample);
}

Expand Down
2 changes: 1 addition & 1 deletion src/constraint/SequentialSampleable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ std::unique_ptr<SampleGenerator> SequentialSampleable::createSampleGenerator()
for (const auto& sampleable : mSampleables)
generators.emplace_back(sampleable->createSampleGenerator());

return dart::common::make_unique<SequentialSampleGenerator>(
return ::dart::common::make_unique<SequentialSampleGenerator>(
mStateSpace, std::move(generators));
}

Expand Down
Loading