Skip to content

Commit

Permalink
Fix failed unit tests on 32-bit machine (#368)
Browse files Browse the repository at this point in the history
  • Loading branch information
dqyi11 authored and jslee02 committed Apr 11, 2018
1 parent 5b2aee9 commit d84453a
Show file tree
Hide file tree
Showing 20 changed files with 83 additions and 44 deletions.
6 changes: 5 additions & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,11 @@

* Robot

* Added Robot, Manipulator, Hand interfaces, and ConcreteRobot, ConcreteManipulator classes. [#325] https://github.com/personalrobotics/aikido/pull/325)
* Added Robot, Manipulator, Hand interfaces, and ConcreteRobot, ConcreteManipulator classes: [#325] https://github.com/personalrobotics/aikido/pull/325)

* Build & Testing & ETC

* Fixed Eigen memory alignment issues on 32bit Ubuntu: [#368](https://github.com/personalrobotics/aikido/pull/368)

### 0.2.0 (2018-01-09)

Expand Down
3 changes: 3 additions & 0 deletions include/aikido/constraint/uniform/RnBoxConstraint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,9 @@ class RBoxConstraint : public constraint::Differentiable,
std::unique_ptr<common::RNG> mRng;
VectorNd mLowerLimits;
VectorNd mUpperLimits;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(VectorNd::NeedsToAlign)
};

using R0BoxConstraint = RBoxConstraint<0>;
Expand Down
3 changes: 3 additions & 0 deletions include/aikido/constraint/uniform/RnConstantSampler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,9 @@ class RConstantSampler : public constraint::Sampleable
private:
std::shared_ptr<statespace::R<N>> mSpace;
VectorNd mValue;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(VectorNd::NeedsToAlign)
};

using R0ConstantSampler = RConstantSampler<0>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,9 @@ class RnConstantSamplerSampleGenerator : public constraint::SampleGenerator
private:
std::shared_ptr<statespace::R<N>> mSpace;
VectorNd mValue;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(VectorNd::NeedsToAlign)
};

//==============================================================================
Expand Down
3 changes: 3 additions & 0 deletions include/aikido/distance/SE2Weighted.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,9 @@ class SE2Weighted : public DistanceMetric
std::shared_ptr<statespace::SE2> mStateSpace;

Eigen::Vector2d mWeights;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

} // namespace distance
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@ namespace vectorfield {
class MoveEndEffectorOffsetVectorField : public BodyNodePoseVectorField
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
/// Constructor
///
/// \param[in] stateSpace MetaSkeleton state space.
Expand Down Expand Up @@ -77,6 +76,9 @@ class MoveEndEffectorOffsetVectorField : public BodyNodePoseVectorField

/// Start pose of the end-effector.
Eigen::Isometry3d mStartPose;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

} // namespace vectorfield
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ namespace vectorfield {
class MoveEndEffectorPoseVectorField : public BodyNodePoseVectorField
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
/// Constructor.
///
/// \param[in] stateSpace MetaSkeleton state space.
Expand Down Expand Up @@ -62,6 +61,9 @@ class MoveEndEffectorPoseVectorField : public BodyNodePoseVectorField

/// Conversion ratio from radius to meter.
double mConversionRatioFromRadiusToMeter;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

} // namespace vectorfield
Expand Down
6 changes: 5 additions & 1 deletion src/common/StepSequence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@
namespace aikido {
namespace common {

constexpr double COMPARE_PRECISION = 1e-7;

//==============================================================================
StepSequence::StepSequence(
double stepSize,
Expand Down Expand Up @@ -111,7 +113,9 @@ void StepSequence::updateLength()

double endPivot = mStartPoint + floorStepRatio * mStepSize;

if (mEndPoint > endPivot)
// When endPivot is close to mEndPoint (below COMPARE_PRECISION threshold), we
// will think endPivot equals to mEndPoint. This is because of numeric issue.
if (std::abs(mEndPoint - endPivot) > COMPARE_PRECISION)
{
if (mIncludeEndPoint)
++mNumSteps;
Expand Down
42 changes: 22 additions & 20 deletions src/planner/vectorfield/VectorFieldPlanner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,17 +165,18 @@ std::unique_ptr<aikido::trajectory::Spline> planToEndEffectorOffset(
metaskeleton, MetaSkeletonStateSaver::Options::POSITIONS);
DART_UNUSED(saver);

auto vectorfield = std::make_shared<MoveEndEffectorOffsetVectorField>(
stateSpace,
metaskeleton,
bn,
direction,
minDistance,
maxDistance,
positionTolerance,
angularTolerance,
initialStepSize,
jointLimitTolerance);
auto vectorfield
= dart::common::make_aligned_shared<MoveEndEffectorOffsetVectorField>(
stateSpace,
metaskeleton,
bn,
direction,
minDistance,
maxDistance,
positionTolerance,
angularTolerance,
initialStepSize,
jointLimitTolerance);

auto compoundConstraint
= std::make_shared<constraint::TestableIntersection>(stateSpace);
Expand Down Expand Up @@ -217,15 +218,16 @@ std::unique_ptr<aikido::trajectory::Spline> planToEndEffectorPose(
metaskeleton, MetaSkeletonStateSaver::Options::POSITIONS);
DART_UNUSED(saver);

auto vectorfield = std::make_shared<MoveEndEffectorPoseVectorField>(
stateSpace,
metaskeleton,
bn,
goalPose,
poseErrorTolerance,
conversionRatioInGeodesicDistance,
initialStepSize,
jointLimitTolerance);
auto vectorfield
= dart::common::make_aligned_shared<MoveEndEffectorPoseVectorField>(
stateSpace,
metaskeleton,
bn,
goalPose,
poseErrorTolerance,
conversionRatioInGeodesicDistance,
initialStepSize,
jointLimitTolerance);

auto compoundConstraint
= std::make_shared<aikido::constraint::TestableIntersection>(stateSpace);
Expand Down
8 changes: 6 additions & 2 deletions src/planner/vectorfield/VectorFieldUtil.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,12 +52,15 @@ class DesiredTwistFunction : public dart::optimizer::Function
grad = mJacobian.transpose() * (mJacobian * qd - mTwist);
}

private:
protected:
/// Twist.
Twist mTwist;

/// Jacobian of Meta Skeleton.
Jacobian mJacobian;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
}

Expand Down Expand Up @@ -123,7 +126,8 @@ bool computeJointVelocityFromTwist(

problem->setInitialGuess(initialGuess);
problem->setObjective(
std::make_shared<DesiredTwistFunction>(desiredTwist, jacobian));
dart::common::make_aligned_shared<DesiredTwistFunction>(
desiredTwist, jacobian));

dart::optimizer::NloptSolver solver(problem, nlopt::LD_LBFGS);
if (!solver.solve())
Expand Down
5 changes: 3 additions & 2 deletions tests/constraint/test_CartesianProductProjectable.cpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include <dart/common/Memory.hpp>
#include <gtest/gtest.h>
#include <aikido/constraint/CartesianProductProjectable.hpp>
#include <aikido/constraint/Projectable.hpp>
Expand All @@ -23,9 +24,9 @@ class CartesianProductProjectableTest : public testing::Test
rvss2 = std::make_shared<R2>();

// Constraints
rvBox1 = std::make_shared<R3BoxConstraint>(
rvBox1 = dart::common::make_aligned_shared<R3BoxConstraint>(
rvss1, nullptr, Eigen::Vector3d(1, 1, 1), Eigen::Vector3d(2, 1, 1));
rvBox2 = std::make_shared<R2BoxConstraint>(
rvBox2 = dart::common::make_aligned_shared<R2BoxConstraint>(
rvss2, nullptr, Eigen::Vector2d(1, 1), Eigen::Vector2d(2, 2));

projectables.push_back(rvBox1);
Expand Down
2 changes: 2 additions & 0 deletions tests/constraint/test_CyclicSampleable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@ using aikido::common::RNGWrapper;
using aikido::common::RNG;
using DefaultRNG = RNGWrapper<std::default_random_engine>;

EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Eigen::Vector2d)

static std::unique_ptr<DefaultRNG> make_rng()
{
return make_unique<RNGWrapper<std::default_random_engine>>(0);
Expand Down
4 changes: 3 additions & 1 deletion tests/constraint/test_FiniteSampleable.cpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include <Eigen/StdVector>
#include <aikido/constraint/FiniteSampleable.hpp>
#include <aikido/statespace/Rn.hpp>
#include <aikido/statespace/StateSpace.hpp>
Expand All @@ -11,6 +12,8 @@ using aikido::constraint::FiniteSampleable;
using aikido::constraint::SampleGenerator;
using State = aikido::statespace::StateSpace::State;

EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Eigen::Vector2d)

TEST(FiniteSampleableTest, ConstructorThrowsOnNullStateSpace)
{
R1 rvss;
Expand Down Expand Up @@ -80,7 +83,6 @@ TEST(FiniteSampleableTest, SingleSampleGenerator)

TEST(FiniteSampleableTest, FiniteSampleGenerator)
{

// Finite-samples
Eigen::Vector2d v1(0, 1);
Eigen::Vector2d v2(2, 3);
Expand Down
2 changes: 1 addition & 1 deletion tests/constraint/test_FrameDifferentiable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class FrameDifferentiableTest : public ::testing::Test
virtual void SetUp()
{

tsr = std::make_shared<TSR>(
tsr = dart::common::make_aligned_shared<TSR>(
std::unique_ptr<RNG>(new RNGWrapper<std::default_random_engine>(0)));

Eigen::MatrixXd Bw = Eigen::Matrix<double, 6, 2>::Zero();
Expand Down
8 changes: 4 additions & 4 deletions tests/constraint/test_RnBoxConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -592,7 +592,7 @@ TEST_F(
//==============================================================================
TEST_F(RnBoxConstraintTests, R2_createSampleGenerator)
{
auto constraint = std::make_shared<R2BoxConstraint>(
auto constraint = dart::common::make_aligned_shared<R2BoxConstraint>(
mR2StateSpace, mRng->clone(), mLowerLimits, mUpperLimits);

auto generator = constraint->createSampleGenerator();
Expand Down Expand Up @@ -632,7 +632,7 @@ TEST_F(RnBoxConstraintTests, R2_createSampleGenerator_RNGIsNull_Throws)
{
// We need to use make_shared here because createSampleGenerator calls
// shared_from_this, provided by enable_shared_from_this.
auto constraint = std::make_shared<R2BoxConstraint>(
auto constraint = dart::common::make_aligned_shared<R2BoxConstraint>(
mR2StateSpace, nullptr, mLowerLimits, mUpperLimits);

EXPECT_THROW({ constraint->createSampleGenerator(); }, std::invalid_argument);
Expand Down Expand Up @@ -660,11 +660,11 @@ TEST_F(RnBoxConstraintTests, R2_createSampleGenerator_Unbounded_Throws)

// We need to use make_shared here because createSampleGenerator calls
// shared_from_this, provided by enable_shared_from_this.
auto unbounded1 = std::make_shared<R2BoxConstraint>(
auto unbounded1 = dart::common::make_aligned_shared<R2BoxConstraint>(
mR2StateSpace, mRng->clone(), noLowerBound, mUpperLimits);
EXPECT_THROW({ unbounded1->createSampleGenerator(); }, std::runtime_error);

auto unbounded2 = std::make_shared<R2BoxConstraint>(
auto unbounded2 = dart::common::make_aligned_shared<R2BoxConstraint>(
mR2StateSpace, mRng->clone(), mLowerLimits, noUpperBound);
EXPECT_THROW({ unbounded2->createSampleGenerator(); }, std::runtime_error);
}
Expand Down
5 changes: 3 additions & 2 deletions tests/constraint/test_RnConstantSampler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,8 +78,9 @@ void testSampleGenerator(int dimension = N)
auto stateSpace = std::make_shared<statespace::R<N>>(dimension);
EXPECT_EQ(stateSpace->getDimension(), dimension);

auto sampler = std::make_shared<constraint::uniform::RConstantSampler<N>>(
stateSpace, value);
auto sampler = dart::common::
make_aligned_shared<constraint::uniform::RConstantSampler<N>>(
stateSpace, value);
EXPECT_EQ(sampler->getStateSpace(), stateSpace);
EXPECT_TRUE(
tests::CompareEigenMatrices(sampler->getConstantValue(), value, 1e-6));
Expand Down
13 changes: 7 additions & 6 deletions tests/constraint/test_SE2BoxConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,9 @@ class SE2BoxConstraintTests : public ::testing::Test

void SetUp() override
{
mSE2StateSpace = std::make_shared<SE2>();
mSE2Distance = std::make_shared<SE2Weighted>(mSE2StateSpace);
mSE2StateSpace = dart::common::make_aligned_shared<SE2>();
mSE2Distance
= dart::common::make_aligned_shared<SE2Weighted>(mSE2StateSpace);
mRng = make_unique<RNGWrapper<std::default_random_engine>>(0);

mLowerLimits = Vector2d(-1., 1.);
Expand Down Expand Up @@ -211,7 +212,7 @@ TEST_F(SE2BoxConstraintTests, projectUnSatisfiedConstraintProjects)
//==============================================================================
TEST_F(SE2BoxConstraintTests, createSampleGenerator)
{
auto constraint = std::make_shared<SE2BoxConstraint>(
auto constraint = dart::common::make_aligned_shared<SE2BoxConstraint>(
mSE2StateSpace, mRng->clone(), mLowerLimits, mUpperLimits);

auto generator = constraint->createSampleGenerator();
Expand All @@ -232,7 +233,7 @@ TEST_F(SE2BoxConstraintTests, createSampleGeneratorThrowOnNUllRNG)
{
// We need to use make_shared here because createSampleGenerator calls
// shared_from_this, provided by enable_shared_from_this.
auto constraint = std::make_shared<SE2BoxConstraint>(
auto constraint = dart::common::make_aligned_shared<SE2BoxConstraint>(
mSE2StateSpace, nullptr, mLowerLimits, mUpperLimits);

EXPECT_THROW({ constraint->createSampleGenerator(); }, std::invalid_argument);
Expand All @@ -249,11 +250,11 @@ TEST_F(SE2BoxConstraintTests, createSampleGeneratorThrowsIfUnbounded)

// We need to use make_shared here because createSampleGenerator calls
// shared_from_this, provided by enable_shared_from_this.
auto unbounded1 = std::make_shared<SE2BoxConstraint>(
auto unbounded1 = dart::common::make_aligned_shared<SE2BoxConstraint>(
mSE2StateSpace, mRng->clone(), noLowerBound, mUpperLimits);
EXPECT_THROW({ unbounded1->createSampleGenerator(); }, std::runtime_error);

auto unbounded2 = std::make_shared<SE2BoxConstraint>(
auto unbounded2 = dart::common::make_aligned_shared<SE2BoxConstraint>(
mSE2StateSpace, mRng->clone(), mLowerLimits, noUpperBound);
EXPECT_THROW({ unbounded2->createSampleGenerator(); }, std::runtime_error);
}
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@ class BarrettHandKinematicSimulationPositionCommandExecutorTest
: public testing::Test
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

void setGeometry(const BodyNodePtr& bn)
{
// Create a BoxShape to be used for both visualization and collision
Expand Down
2 changes: 2 additions & 0 deletions tests/planner/parabolic/test_ParabolicTimer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@ using aikido::planner::parabolic::convertToSpline;

class ParabolicTimerTests : public ::testing::Test
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
protected:
void SetUp() override
{
Expand Down
2 changes: 0 additions & 2 deletions tests/planner/parabolic/test_TimePostProcessor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,6 @@ using aikido::planner::parabolic::ParabolicTimer;

class TimePostProcessorTests : public ::testing::Test
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
protected:
void SetUp() override
{
Expand Down

0 comments on commit d84453a

Please sign in to comment.