Skip to content

Commit

Permalink
Make format
Browse files Browse the repository at this point in the history
  • Loading branch information
egordon committed Aug 1, 2019
1 parent 5f35b80 commit e2c97c2
Show file tree
Hide file tree
Showing 23 changed files with 104 additions and 120 deletions.
11 changes: 7 additions & 4 deletions include/aikido/constraint/FiniteSampleable.hpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#ifndef AIKIDO_CONSTRAINT_FINITESAMPLEABLE_HPP_
#define AIKIDO_CONSTRAINT_FINITESAMPLEABLE_HPP_

#include "Sampleable.hpp"
#include "aikido/statespace/dart/MetaSkeletonStateSpace.hpp"
#include "Sampleable.hpp"

namespace aikido {
namespace constraint {
Expand All @@ -18,15 +18,17 @@ class FiniteSampleable : public Sampleable
/// \param _state The only sample in this constraint.
FiniteSampleable(
statespace::StateSpacePtr _stateSpace,
const aikido::statespace::dart::MetaSkeletonStateSpace::ScopedState& _state);
const aikido::statespace::dart::MetaSkeletonStateSpace::ScopedState&
_state);

/// Constructor for multiple samples.
/// \param _stateSpace StateSpace in which _states belong.
/// \param _states Samples in this constraint.
/// SampleGenerator will generate samples in this order.
FiniteSampleable(
statespace::StateSpacePtr _stateSpace,
const std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::ScopedState>& _states);
const std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::
ScopedState>& _states);

FiniteSampleable(const FiniteSampleable& other) = delete;
FiniteSampleable(FiniteSampleable&& other) = delete;
Expand All @@ -44,7 +46,8 @@ class FiniteSampleable : public Sampleable

private:
statespace::ConstStateSpacePtr mStateSpace;
std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::ScopedState> mStates;
std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::ScopedState>
mStates;
};

} // namespace constraint
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,8 +124,7 @@ template <int N>
std::unique_ptr<constraint::SampleGenerator>
RConstantSampler<N>::createSampleGenerator() const
{
return std::make_unique<RnConstantSamplerSampleGenerator<N>>(
mSpace, mValue);
return std::make_unique<RnConstantSamplerSampleGenerator<N>>(mSpace, mValue);
}

//==============================================================================
Expand Down
4 changes: 2 additions & 2 deletions include/aikido/distance/NominalConfigurationRanker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,8 @@ class NominalConfigurationRanker : public ConfigurationRanker
/// \param[in] nominalConfiguration Nominal configuration. The current
/// configuration of \c metaSkeleton is considered if set to \c nullptr.
// NominalConfigurationRanker(
// statespace::dart::ConstMetaSkeletonStateSpacePtr metaSkeletonStateSpace,
// statespace::dart::ConstMetaSkeletonStateSpacePtr
// metaSkeletonStateSpace,
// ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
// std::vector<double> weights = std::vector<double>(),
// const statespace::CartesianProduct::State* nominalConfiguration
Expand All @@ -34,7 +35,6 @@ class NominalConfigurationRanker : public ConfigurationRanker
std::vector<double> weights,
statespace::CartesianProduct::ScopedState nominalConfiguration);


protected:
/// Returns cost as distance from the Nominal Configuration.
double evaluateConfiguration(
Expand Down
4 changes: 2 additions & 2 deletions include/aikido/trajectory/util.hpp
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
#ifndef AIKIDO_TRAJECTORY_UTIL_HPP_
#define AIKIDO_TRAJECTORY_UTIL_HPP_

#include <dart/dart.hpp>
#include "aikido/statespace/dart/MetaSkeletonStateSpace.hpp"
#include "aikido/trajectory/Interpolated.hpp"
#include "aikido/trajectory/Spline.hpp"
#include "aikido/statespace/dart/MetaSkeletonStateSpace.hpp"
#include <dart/dart.hpp>

namespace aikido {
namespace trajectory {
Expand Down
20 changes: 11 additions & 9 deletions src/constraint/FiniteSampleable.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include <aikido/constraint/FiniteSampleable.hpp>
#include <iostream>
#include <dart/common/StlHelpers.hpp>
#include <aikido/constraint/FiniteSampleable.hpp>

namespace aikido {
namespace constraint {
Expand All @@ -12,7 +12,8 @@ class FiniteSampleGenerator : public SampleGenerator
// For internal use only.
FiniteSampleGenerator(
statespace::ConstStateSpacePtr _stateSpace,
const std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::ScopedState>& _states);
const std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::
ScopedState>& _states);

FiniteSampleGenerator(const FiniteSampleGenerator&) = delete;
FiniteSampleGenerator(FiniteSampleGenerator&& other) = delete;
Expand All @@ -36,7 +37,8 @@ class FiniteSampleGenerator : public SampleGenerator

private:
statespace::ConstStateSpacePtr mStateSpace;
std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::ScopedState> mStates;
std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::ScopedState>
mStates;
int mIndex;

friend class FiniteSampleable;
Expand All @@ -45,9 +47,9 @@ class FiniteSampleGenerator : public SampleGenerator
//==============================================================================
FiniteSampleGenerator::FiniteSampleGenerator(
statespace::ConstStateSpacePtr _stateSpace,
const std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::ScopedState>& _states)
: mStateSpace(std::move(_stateSpace))
, mIndex(0)
const std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::
ScopedState>& _states)
: mStateSpace(std::move(_stateSpace)), mIndex(0)
{
if (!mStateSpace)
throw std::invalid_argument("StateSpacePtr is nullptr.");
Expand Down Expand Up @@ -117,7 +119,8 @@ FiniteSampleable::FiniteSampleable(
//==============================================================================
FiniteSampleable::FiniteSampleable(
statespace::StateSpacePtr _stateSpace,
const std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::ScopedState>& _states)
const std::vector<aikido::statespace::dart::MetaSkeletonStateSpace::
ScopedState>& _states)
: mStateSpace(std::move(_stateSpace))
{
if (!mStateSpace)
Expand Down Expand Up @@ -152,8 +155,7 @@ statespace::ConstStateSpacePtr FiniteSampleable::getStateSpace() const
//==============================================================================
std::unique_ptr<SampleGenerator> FiniteSampleable::createSampleGenerator() const
{
return std::make_unique<FiniteSampleGenerator>(
mStateSpace, mStates);
return std::make_unique<FiniteSampleGenerator>(mStateSpace, mStates);
}

} // namespace constraint
Expand Down
5 changes: 3 additions & 2 deletions src/constraint/SequentialSampleable.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#include "aikido/constraint/SequentialSampleable.hpp"

#include <iostream>
#include <dart/common/Console.hpp>
#include <dart/common/Memory.hpp>
#include <iostream>

namespace aikido {
namespace constraint {
Expand Down Expand Up @@ -93,7 +93,8 @@ bool SequentialSampleGenerator::sample(statespace::StateSpace::State* state)
{
// Eigen::VectorXd positions;
// mStateSpace->logMap(state, positions);
// std::cout << "SequentialSampleGenerator " << mIndex << "/ " << mGenerators.size() << " " << positions.transpose() << std::endl;
// std::cout << "SequentialSampleGenerator " << mIndex << "/ " <<
// mGenerators.size() << " " << positions.transpose() << std::endl;
return true;
}

Expand Down
3 changes: 2 additions & 1 deletion src/constraint/dart/CollisionFree.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,8 @@ bool CollisionFree::isSatisfied(
// collisionFreeOutcome = new CollisionFreeOutcome();
// }
auto _outcome = this->createOutcome();
auto collisionFreeOutcome = dynamic_cast<CollisionFreeOutcome*>(_outcome.get());
auto collisionFreeOutcome
= dynamic_cast<CollisionFreeOutcome*>(_outcome.get());

auto skelStatePtr = static_cast<const aikido::statespace::dart::
MetaSkeletonStateSpace::State*>(_state);
Expand Down
8 changes: 4 additions & 4 deletions src/constraint/dart/InverseKinematicsSampleable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,12 +220,12 @@ bool IkSampleGenerator::sample(statespace::StateSpace::State* _state)

mInverseKinematics->getTarget()->setTransform(poseState.getIsometry());

// Run the IK solver. If it succeeds, return the solution.
#if DART_VERSION_AT_LEAST(6, 8, 0)
// Run the IK solver. If it succeeds, return the solution.
#if DART_VERSION_AT_LEAST(6, 8, 0)
if (mInverseKinematics->solveAndApply(true))
#else
#else
if (mInverseKinematics->solve(true))
#endif
#endif
{
mMetaSkeletonStateSpace->getState(mMetaSkeleton.get(), outputState);
return true;
Expand Down
2 changes: 1 addition & 1 deletion src/control/ros/RosTrajectoryExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ std::future<void> RosTrajectoryExecutor::execute(
goal,
boost::bind(&RosTrajectoryExecutor::transitionCallback, this, _1));

std::cout << "Returning future" << std::endl;
std::cout << "Returning future" << std::endl;
return mPromise->get_future();
}
}
Expand Down
10 changes: 5 additions & 5 deletions src/distance/NominalConfigurationRanker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,11 @@ using ::dart::dynamics::ConstMetaSkeletonPtr;

//==============================================================================
NominalConfigurationRanker::NominalConfigurationRanker(
statespace::dart::ConstMetaSkeletonStateSpacePtr metaSkeletonStateSpace,
::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
std::vector<double> weights,
statespace::CartesianProduct::ScopedState nominalConfiguration)
: ConfigurationRanker(
statespace::dart::ConstMetaSkeletonStateSpacePtr metaSkeletonStateSpace,
::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
std::vector<double> weights,
statespace::CartesianProduct::ScopedState nominalConfiguration)
: ConfigurationRanker(
std::move(metaSkeletonStateSpace), std::move(metaSkeleton), weights)
, mNominalConfiguration(std::move(nominalConfiguration))
{
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 @@ -70,8 +70,7 @@ std::unique_ptr<aikido::trajectory::Spline> convertToSpline(

// create spline
auto outputTrajectory
= std::make_unique<aikido::trajectory::Spline>(
stateSpace, startTime);
= std::make_unique<aikido::trajectory::Spline>(stateSpace, startTime);

// create a sequence of time steps from start time to end time by time step
aikido::common::StepSequence sequence(
Expand Down
5 changes: 2 additions & 3 deletions src/planner/ompl/Planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -477,9 +477,8 @@ std::unique_ptr<trajectory::Interpolated> toInterpolatedTrajectory(
const ::ompl::geometric::PathGeometric& _path,
statespace::InterpolatorPtr _interpolator)
{
auto returnInterpolated
= std::make_unique<trajectory::Interpolated>(
_interpolator->getStateSpace(), std::move(_interpolator));
auto returnInterpolated = std::make_unique<trajectory::Interpolated>(
_interpolator->getStateSpace(), std::move(_interpolator));

for (std::size_t idx = 0; idx < _path.getStateCount(); ++idx)
{
Expand Down
9 changes: 5 additions & 4 deletions src/planner/vectorfield/VectorFieldUtil.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,11 +129,12 @@ bool computeJointVelocityFromTwist(
dart::common::make_aligned_shared<DesiredTwistFunction>(
desiredTwist, jacobian));

#if DART_VERSION_AT_LEAST(6, 9, 0)
dart::optimizer::NloptSolver solver(problem, dart::optimizer::NloptSolver::Algorithm::LD_LBFGS);
#else
#if DART_VERSION_AT_LEAST(6, 9, 0)
dart::optimizer::NloptSolver solver(
problem, dart::optimizer::NloptSolver::Algorithm::LD_LBFGS);
#else
dart::optimizer::NloptSolver solver(problem, nlopt::LD_LBFGS);
#endif
#endif
if (!solver.solve())
{
return false;
Expand Down
5 changes: 2 additions & 3 deletions src/planner/vectorfield/detail/VectorFieldIntegrator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,9 +53,8 @@ std::unique_ptr<aikido::trajectory::Interpolated> convertToInterpolated(
auto interpolator
= std::make_shared<const aikido::statespace::GeodesicInterpolator>(
stateSpace);
auto outputTrajectory
= std::make_unique<aikido::trajectory::Interpolated>(
stateSpace, interpolator);
auto outputTrajectory = std::make_unique<aikido::trajectory::Interpolated>(
stateSpace, interpolator);

auto currState = stateSpace->createState();
for (const auto& knot : knots)
Expand Down
Loading

0 comments on commit e2c97c2

Please sign in to comment.