Skip to content

Commit

Permalink
Suppress more warnings per Apple Clang 4.0.0
Browse files Browse the repository at this point in the history
  • Loading branch information
jslee02 committed Apr 28, 2017
1 parent f7c93b3 commit b8f60cf
Show file tree
Hide file tree
Showing 10 changed files with 15 additions and 38 deletions.
7 changes: 0 additions & 7 deletions tests/constraint/test_DartHelpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,6 @@ using aikido::constraint::createProjectableBoundsFor;
using aikido::constraint::createTestableBoundsFor;
using aikido::constraint::createSampleableBoundsFor;

static inline Vector1d make_vector(double _x)
{
Vector1d matrix;
matrix(0, 0) = _x;
return matrix;
}

//=============================================================================
class RnJointHelpersTests : public ::testing::Test
{
Expand Down
8 changes: 0 additions & 8 deletions tests/constraint/test_TSR.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,6 @@ using dart::common::make_unique;

using DefaultRNG = RNGWrapper<std::default_random_engine>;

static inline std::unique_ptr<DefaultRNG> make_rng()
{
return make_unique<RNGWrapper<std::default_random_engine>>(0);
}

TEST(TSR, InitializesToIdentity)
{
TSR tsr;
Expand Down Expand Up @@ -468,6 +463,3 @@ TEST(TSR, getSE3EqualToGetStateSpace)

EXPECT_EQ(se3space, space);
}



Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@ static BodyNode::Properties create_BodyNodeProperties(const std::string& _name)
return properties;
}

const static std::chrono::milliseconds stepTime{100};
const static std::chrono::nanoseconds waitTime{1};

class BarrettFingerKinematicSimulationPositionCommandExecutorTest : public testing::Test
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ static BodyNode::Properties create_BodyNodeProperties(const std::string& _name)
return properties;
}

const static std::chrono::milliseconds stepTime{100};
const static std::chrono::nanoseconds waitTime{1};

class BarrettFingerKinematicSimulationSpreadCommandExecutorTest : public testing::Test
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,6 @@ using namespace dart::dynamics;
using namespace dart::collision;
using namespace dart::simulation;

const static std::chrono::milliseconds stepTime{100};

static BodyNode::Properties create_BodyNodeProperties(const std::string& _name)
{
BodyNode::Properties properties;
Expand Down
8 changes: 3 additions & 5 deletions tests/planner/ompl/test_GoalRegion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class GoalRegionTest : public PlannerTest

}
std::shared_ptr<GeometricStateSpace> gSpace;
boost::shared_ptr<::ompl::base::SpaceInformation> si;
::ompl::base::SpaceInformationPtr si;
};

TEST_F(GoalRegionTest, ThrowsOnNullSpaceInformation)
Expand Down Expand Up @@ -60,8 +60,7 @@ TEST_F(GoalRegionTest, ThrowsOnTestableGeneratorMismatch)
TEST_F(GoalRegionTest, DifferentSample)
{
auto testable = std::make_shared<PassingConstraint>(stateSpace);
GoalRegion gr(si, std::move(testable),
std::move(sampler->createSampleGenerator()));
GoalRegion gr(si, std::move(testable), sampler->createSampleGenerator());

auto state1 = si->allocState();
auto state2 = si->allocState();
Expand All @@ -78,8 +77,7 @@ TEST_F(GoalRegionTest, DifferentSample)
TEST_F(GoalRegionTest, ValidSample)
{
auto testable = std::make_shared<PassingConstraint>(stateSpace);
GoalRegion gr(si, std::move(testable),
std::move(sampler->createSampleGenerator()));
GoalRegion gr(si, std::move(testable), sampler->createSampleGenerator());

auto state1 = si->allocState();

Expand Down
5 changes: 3 additions & 2 deletions tests/planner/ompl/test_MotionValidator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

using aikido::statespace::dart::MetaSkeletonStateSpace;
using aikido::planner::ompl::MotionValidator;
using aikido::planner::ompl::ompl_make_shared;

/// This test creates a world with a translational robot
/// and a .2x.2x.2 block obstacle at the origin
Expand All @@ -28,8 +29,8 @@ class MotionValidatorTest : public ::testing::Test
std::make_shared<MockTranslationalRobotConstraint>(
stateSpace, Eigen::Vector3d(-0.1, -0.1, -0.1),
Eigen::Vector3d(0.1, 0.1, 0.1));
::ompl::base::StateValidityCheckerPtr vchecker =
boost::make_shared<aikido::planner::ompl::StateValidityChecker>(
auto vchecker =
ompl_make_shared<aikido::planner::ompl::StateValidityChecker>(
si, mockCollisionConstraint);
si->setStateValidityChecker(vchecker);
validator = std::make_shared<MotionValidator>(si, 0.1);
Expand Down
8 changes: 4 additions & 4 deletions tests/planner/ompl/test_OMPLPlanner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ using StateSpace = aikido::statespace::dart::MetaSkeletonStateSpace;
using aikido::planner::ompl::getSpaceInformation;
using aikido::planner::ompl::CRRT;
using aikido::planner::ompl::CRRTConnect;
using aikido::planner::ompl::ompl_dynamic_pointer_cast;

TEST_F(PlannerTest, PlanToConfiguration)
{
Expand Down Expand Up @@ -471,7 +472,7 @@ TEST_F(PlannerTest, GetSpaceInformationCreatesGeometricStateSpace)
std::move(sampler), std::move(collConstraint),
std::move(boundsConstraint), std::move(boundsProjection), 0.1);

auto ss = boost::dynamic_pointer_cast<aikido::planner::ompl::GeometricStateSpace>(
auto ss = ompl_dynamic_pointer_cast<aikido::planner::ompl::GeometricStateSpace>(
si->getStateSpace());
EXPECT_FALSE(ss == nullptr);
}
Expand All @@ -483,7 +484,7 @@ TEST_F(PlannerTest, GetSpaceInformationCreatesValidityChecker)
std::move(sampler), std::move(collConstraint),
std::move(boundsConstraint), std::move(boundsProjection), 0.1);

auto vc = boost::dynamic_pointer_cast<aikido::planner::ompl::StateValidityChecker>(
auto vc = ompl_dynamic_pointer_cast<aikido::planner::ompl::StateValidityChecker>(
si->getStateValidityChecker());
EXPECT_FALSE(vc == nullptr);
}
Expand All @@ -495,8 +496,7 @@ TEST_F(PlannerTest, GetSpaceInformationCreatesMotionValidator)
std::move(sampler), std::move(collConstraint),
std::move(boundsConstraint), std::move(boundsProjection), 0.1);

auto mvalidator = boost::dynamic_pointer_cast<aikido::planner::ompl::MotionValidator>(
auto mvalidator = ompl_dynamic_pointer_cast<aikido::planner::ompl::MotionValidator>(
si->getMotionValidator());
EXPECT_FALSE(mvalidator == nullptr);
}

11 changes: 4 additions & 7 deletions tests/planner/ompl/test_StateSampler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ class StateSamplerTest : public PlannerTest

TEST_F(StateSamplerTest, ThrowsOnNullStateSpace)
{
EXPECT_THROW(StateSampler(0, std::move(sampler->createSampleGenerator())),
EXPECT_THROW(StateSampler(0, sampler->createSampleGenerator()),
std::invalid_argument);
}

Expand Down Expand Up @@ -60,8 +60,7 @@ TEST_F(StateSamplerTest, SampleUniformGeneratorFailsSample)

TEST_F(StateSamplerTest, SampleUniformValid)
{
StateSampler ssampler(gSpace.get(),
std::move(sampler->createSampleGenerator()));
StateSampler ssampler(gSpace.get(), sampler->createSampleGenerator());
auto s1 = gSpace->allocState()->as<GeometricStateSpace::StateType>();
auto s2 = gSpace->allocState()->as<GeometricStateSpace::StateType>();

Expand All @@ -76,8 +75,7 @@ TEST_F(StateSamplerTest, SampleUniformValid)

TEST_F(StateSamplerTest, SampleUniformNearAlwaysThrows)
{
StateSampler ssampler(gSpace.get(),
std::move(sampler->createSampleGenerator()));
StateSampler ssampler(gSpace.get(), sampler->createSampleGenerator());
auto s1 = gSpace->allocState()->as<GeometricStateSpace::StateType>();
auto s2 = gSpace->allocState()->as<GeometricStateSpace::StateType>();

Expand All @@ -89,8 +87,7 @@ TEST_F(StateSamplerTest, SampleUniformNearAlwaysThrows)

TEST_F(StateSamplerTest, SampleGaussianAlwaysThrows)
{
StateSampler ssampler(gSpace.get(),
std::move(sampler->createSampleGenerator()));
StateSampler ssampler(gSpace.get(), sampler->createSampleGenerator());
auto s1 = gSpace->allocState()->as<GeometricStateSpace::StateType>();
auto s2 = gSpace->allocState()->as<GeometricStateSpace::StateType>();

Expand Down
2 changes: 1 addition & 1 deletion tests/planner/ompl/test_ValidityChecker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ class StateValidityCheckerTest : public PlannerTest
boundsConstraint, boundsProjection, 0.1);
}
std::shared_ptr<GeometricStateSpace> gSpace;
boost::shared_ptr<::ompl::base::SpaceInformation> si;
::ompl::base::SpaceInformationPtr si;
};

TEST_F(StateValidityCheckerTest, ThrowsOnNullSpaceInformation)
Expand Down

0 comments on commit b8f60cf

Please sign in to comment.