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

Explicitly call dart::common::make_unique to get over std ambiguity. #531

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all 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
3 changes: 1 addition & 2 deletions src/distance/ConfigurationRanker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@ namespace distance {

using statespace::dart::ConstMetaSkeletonStateSpacePtr;
using statespace::dart::MetaSkeletonStateSpace;
using dart::common::make_unique;
using ::dart::dynamics::ConstMetaSkeletonPtr;

//==============================================================================
Expand Down Expand Up @@ -63,7 +62,7 @@ ConfigurationRanker::ConfigurationRanker(
metrics.emplace_back(std::make_pair(std::move(metric), weights[i]));
}

mDistanceMetric = make_unique<CartesianProductWeighted>(
mDistanceMetric = ::dart::common::make_unique<CartesianProductWeighted>(
std::move(_sspace), std::move(metrics));
}

Expand Down
3 changes: 1 addition & 2 deletions src/planner/kunzretimer/KunzRetimer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
#include "Path.h"
#include "Trajectory.h"

using dart::common::make_unique;
using aikido::statespace::dart::MetaSkeletonStateSpace;
using aikido::statespace::ConstStateSpacePtr;
using aikido::trajectory::toR1JointTrajectory;
Expand Down Expand Up @@ -52,7 +51,7 @@ std::unique_ptr<Path> convertToKunzPath(
stateSpace->logMap(tmpState, tmpVec);
waypoints.push_back(tmpVec);
}
auto path = make_unique<Path>(waypoints, maxDeviation);
auto path = ::dart::common::make_unique<Path>(waypoints, maxDeviation);
return path;
}

Expand Down
7 changes: 3 additions & 4 deletions src/planner/parabolic/ParabolicUtil.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ using aikido::statespace::dart::MetaSkeletonStateSpace;
using aikido::trajectory::toR1JointTrajectory;
using aikido::trajectory::ConstInterpolatedPtr;
using aikido::trajectory::ConstSplinePtr;
using dart::common::make_unique;

using CubicSplineProblem
= aikido::common::SplineProblem<double, int, 4, Eigen::Dynamic, 2>;
Expand Down Expand Up @@ -102,7 +101,7 @@ std::unique_ptr<aikido::trajectory::Spline> convertToSpline(
Eigen::VectorXd positionPrev, velocityPrev;
evaluateAtTime(_inputPath, timePrev, positionPrev, velocityPrev);

auto _outputTrajectory = make_unique<aikido::trajectory::Spline>(
auto _outputTrajectory = ::dart::common::make_unique<aikido::trajectory::Spline>(
_stateSpace, timePrev + _startTime);
auto segmentStartState = _stateSpace->createState();

Expand Down Expand Up @@ -163,7 +162,7 @@ std::unique_ptr<ParabolicRamp::DynamicPath> convertToDynamicPath(
velocities.emplace_back(toVector(tangentVector));
}

auto outputPath = make_unique<ParabolicRamp::DynamicPath>();
auto outputPath = ::dart::common::make_unique<ParabolicRamp::DynamicPath>();
outputPath->Init(toVector(_maxVelocity), toVector(_maxAcceleration));
if (_preserveWaypointVelocity)
{
Expand Down Expand Up @@ -202,7 +201,7 @@ std::unique_ptr<ParabolicRamp::DynamicPath> convertToDynamicPath(
milestones.emplace_back(toVector(currVec));
}

auto outputPath = make_unique<ParabolicRamp::DynamicPath>();
auto outputPath = ::dart::common::make_unique<ParabolicRamp::DynamicPath>();
outputPath->Init(toVector(_maxVelocity), toVector(_maxAcceleration));
outputPath->SetMilestones(milestones);
if (!outputPath->IsValid())
Expand Down
9 changes: 4 additions & 5 deletions src/trajectory/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@ using aikido::statespace::GeodesicInterpolator;
using aikido::statespace::StateSpacePtr;
using aikido::statespace::dart::MetaSkeletonStateSpace;
using aikido::statespace::dart::MetaSkeletonStateSpacePtr;
using dart::common::make_unique;

using Eigen::Vector2d;
using LinearSplineProblem
Expand Down Expand Up @@ -89,7 +88,7 @@ UniqueSplinePtr convertToSpline(const Interpolated& inputTrajectory)
throw std::invalid_argument("Trajectory is empty.");

auto outputTrajectory
= make_unique<Spline>(stateSpace, inputTrajectory.getStartTime());
= ::dart::common::make_unique<Spline>(stateSpace, inputTrajectory.getStartTime());

Eigen::VectorXd currentVec, nextVec;
for (std::size_t iwaypoint = 0; iwaypoint < numWaypoints - 1; ++iwaypoint)
Expand Down Expand Up @@ -128,7 +127,7 @@ UniqueInterpolatedPtr concatenate(
if (traj1.getInterpolator() != traj2.getInterpolator())
throw std::runtime_error("Interpolator mismatch");

auto outputTrajectory = make_unique<Interpolated>(
auto outputTrajectory = ::dart::common::make_unique<Interpolated>(
traj1.getStateSpace(), traj1.getInterpolator());
if (traj1.getNumWaypoints() > 1u)
{
Expand Down Expand Up @@ -197,7 +196,7 @@ UniqueSplinePtr createPartialTrajectory(

const auto stateSpace = traj.getStateSpace();
const int dimension = static_cast<int>(stateSpace->getDimension());
auto outputTrajectory = make_unique<Spline>(stateSpace, traj.getStartTime());
auto outputTrajectory = ::dart::common::make_unique<Spline>(stateSpace, traj.getStartTime());

double currSegmentStartTime = traj.getStartTime();
double currSegmentEndTime = currSegmentStartTime;
Expand Down Expand Up @@ -279,7 +278,7 @@ UniqueInterpolatedPtr toR1JointTrajectory(const Interpolated& trajectory)

auto rSpace = std::make_shared<CartesianProduct>(subspaces);
auto rInterpolator = std::make_shared<GeodesicInterpolator>(rSpace);
auto rTrajectory = make_unique<Interpolated>(rSpace, rInterpolator);
auto rTrajectory = ::dart::common::make_unique<Interpolated>(rSpace, rInterpolator);

Eigen::VectorXd sourceVector(space->getDimension());
auto sourceState = rSpace->createState();
Expand Down