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

Remove use of deprecated dart::common::make_unique #532

Merged
merged 12 commits into from
Jul 17, 2019
2 changes: 1 addition & 1 deletion .ci/script_cmake.sh
Original file line number Diff line number Diff line change
Expand Up @@ -8,4 +8,4 @@ mkdir build
cd build
cmake -DCMAKE_BUILD_TYPE=${BUILD_TYPE} -DTREAT_WARNINGS_AS_ERRORS=ON ..
make -j4 tests
make test
ctest
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just to see if it makes any difference that turned out not. Feel free to revert it.

2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ matrix:
services: docker

- os: osx
osx_image: xcode9.3
osx_image: xcode11
compiler: clang
env:
- BUILD_NAME=XCODE93_CMAKE_RELEASE
Expand Down
18 changes: 18 additions & 0 deletions Brewfile
Original file line number Diff line number Diff line change
@@ -1,6 +1,24 @@
brew 'boost'
brew 'dartsim'
brew 'eigen'
brew 'libmicrohttpd'
brew 'ompl'
brew 'tinyxml2'
brew 'yaml-cpp'

# Install dartsim dependencies explicitly because, for some unknown reasons,
# Travis CI + Homebrew fails to find the dartsim dependencies.
brew 'assimp'
brew 'boost'
brew 'bullet'
brew 'eigen'
brew 'fcl'
brew 'flann'
brew 'ipopt'
brew 'libccd'
brew 'nlopt'
brew 'octomap'
brew 'ode'
brew 'open-scene-graph'
brew 'tinyxml2'
brew 'urdfdom'
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ execution on real robots.
AIKIDO depends on [ROS]. You should [install ROS](http://wiki.ros.org/indigo/Installation/Ubuntu) by adding the ROS repository to your `sources.list` as follows. We encourage users to install [`indigo`](http://wiki.ros.org/indigo).
```shell
$ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
$ sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116
$ sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
$ sudo apt-get update
$ sudo apt-get install ros-indigo-actionlib ros-indigo-geometry-msgs ros-indigo-interactive-markers ros-indigo-roscpp ros-indigo-std-msgs ros-indigo-tf ros-indigo-trajectory-msgs ros-indigo-visualization-msgs
```
Expand Down
23 changes: 23 additions & 0 deletions include/aikido/common/detail/memory-impl.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
#ifndef AIKIDO_COMMON_DETAIL_MEMORY_IMPL_HPP_
#define AIKIDO_COMMON_DETAIL_MEMORY_IMPL_HPP_

#include "aikido/common/memory.hpp"

namespace aikido {
namespace common {

//==============================================================================
template<typename T, typename... Args>
::std::unique_ptr<T> make_unique(Args&&... args)
{
#if __cplusplus < 201300
return ::std::unique_ptr<T>(new T(::std::forward<Args>(args)...));
#else
return ::std::make_unique<T>(::std::forward<Args>(args)...);
#endif
}

} // namespace common
} // namespace aikido

#endif // AIKIDO_COMMON_DETAIL_MEMORY_IMPL_HPP_
17 changes: 17 additions & 0 deletions include/aikido/common/memory.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
#ifndef AIKIDO_COMMON_MEMORY_HPP_
#define AIKIDO_COMMON_MEMORY_HPP_

#include <memory>

namespace aikido {
namespace common {

template <typename T, typename... Args>
::std::unique_ptr<T> make_unique(Args&&... args);

} // namespace common
} // namespace aikido

#include "aikido/common/detail/memory-impl.hpp"

#endif // AIKIDO_COMMON_MEMORY_HPP_
1 change: 1 addition & 0 deletions include/aikido/constraint/Differentiable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ enum class ConstraintType
class Differentiable
{
public:
/// Destructor
virtual ~Differentiable() = default;

/// Gets the StateSpace that this constraint operates on.
Expand Down
3 changes: 3 additions & 0 deletions include/aikido/constraint/TestableOutcome.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,9 @@ namespace constraint {
class TestableOutcome
{
public:
/// Destructor
virtual ~TestableOutcome() = default;

/// Returns true if isSatisfied call this outcome object was passed to
/// returned true. False otherwise.
virtual bool isSatisfied() const = 0;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include <sstream>
#include <dart/common/StlHelpers.hpp>
#include "aikido/common/memory.hpp"
#include "aikido/common/metaprogramming.hpp"
#include "aikido/constraint/Satisfied.hpp"
#include "aikido/constraint/uniform/RnBoxConstraint.hpp"
Expand Down Expand Up @@ -67,15 +67,15 @@ std::unique_ptr<OutputConstraint> createBoxConstraint(

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

return ::dart::common::make_unique<uniform::R0ConstantSampler>(
return ::aikido::common::make_unique<uniform::R0ConstantSampler>(
std::move(_stateSpace), positions);
}
};
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include <stdexcept>
#include <dart/dart.hpp>
#include "aikido/common/memory.hpp"
#include "aikido/constraint/uniform/RnConstantSampler.hpp"

#undef dtwarn
Expand Down Expand Up @@ -124,7 +125,7 @@ template <int N>
std::unique_ptr<constraint::SampleGenerator>
RConstantSampler<N>::createSampleGenerator() const
{
return ::dart::common::make_unique<RnConstantSamplerSampleGenerator<N>>(
return ::aikido::common::make_unique<RnConstantSamplerSampleGenerator<N>>(
mSpace, mValue);
}

Expand Down
20 changes: 10 additions & 10 deletions include/aikido/distance/detail/defaults-impl.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include <dart/common/StlHelpers.hpp>
#include "aikido/common/memory.hpp"

#include "../../common/metaprogramming.hpp"
#include "../../statespace/CartesianProduct.hpp"
Expand Down Expand Up @@ -31,7 +31,7 @@ struct createDistanceMetricFor_impl<const statespace::R0>
{
static Ptr create(std::shared_ptr<const statespace::R0> _sspace)
{
return ::dart::common::make_unique<R0Euclidean>(std::move(_sspace));
return ::aikido::common::make_unique<R0Euclidean>(std::move(_sspace));
}
};

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

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

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

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

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

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

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

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

Expand Down
2 changes: 1 addition & 1 deletion include/aikido/io/detail/yaml_extension.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <sstream>
#include <unordered_map>
#include <Eigen/Dense>
#include <dart/common/StlHelpers.hpp>
#include "aikido/common/memory.hpp"
#include <yaml-cpp/yaml.h>

namespace aikido {
Expand Down
3 changes: 3 additions & 0 deletions include/aikido/planner/vectorfield/VectorField.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,9 @@ class VectorField
/// \param[in] stateSpace State space that vector field is defined in.
explicit VectorField(aikido::statespace::ConstStateSpacePtr stateSpace);

/// Destructor
virtual ~VectorField() = default;

/// Vectorfield callback function.
///
/// \param[in] state Statespace state.
Expand Down
Loading