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

changes made to build without warnings #143

Merged
merged 29 commits into from
Apr 11, 2017
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
Show all changes
29 commits
Select commit Hold shift + click to select a range
926d505
changes made to build without warnings
aditya-vk Mar 24, 2017
a41a598
pr suggestions addressed. need to ignore external for warnings
aditya-vk Mar 31, 2017
9b3a985
addressed the suggestions on PR
aditya-vk Mar 31, 2017
823be29
removed unused typedef. removed unnecessary comments
aditya-vk Apr 4, 2017
a8db4b5
Merge remote-tracking branch 'origin/master' into werror_clean
jslee02 Apr 4, 2017
e859eb9
Suppress warning in PolynomialConstraint.cpp
jslee02 Apr 4, 2017
d6884b4
Resolve some of warnings
jslee02 Apr 5, 2017
6ba97bc
Resolve some of warnings in tests
jslee02 Apr 5, 2017
8779ee9
fix warnings with -Wall -Werror; tests included
aditya-vk Apr 6, 2017
9b621e4
nitpick
aditya-vk Apr 6, 2017
91cb9a5
fix warnings
aditya-vk Apr 6, 2017
1db0113
fix warnings ompl
aditya-vk Apr 6, 2017
62395e7
minor fixes with pedantic. tests to be fixed still
aditya-vk Apr 7, 2017
bffe6ec
fixed warning with pedantic for tests as well
aditya-vk Apr 7, 2017
54d8a0d
Merge branch 'master' into werror_clean
jslee02 Apr 7, 2017
6366a4b
nitpicks
aditya-vk Apr 9, 2017
69f689b
added SYSTEM flag for Google Test .h files
aditya-vk Apr 9, 2017
ecce168
added SYSTEM flag to Google Test .h files
aditya-vk Apr 9, 2017
5180540
Suppress warning from RnConstantSampler.cpp
jslee02 Apr 10, 2017
e5f0d0f
Enable -Wextra and fixes the entailed warnings
jslee02 Apr 10, 2017
d507361
Add back accidentally removed lines in test_NonColliding.cpp
jslee02 Apr 10, 2017
16c7778
Enable -Wextra and fixes the entailed warnings
jslee02 Apr 10, 2017
b132bd0
Rollback changes made on gtest
jslee02 Apr 10, 2017
0eefb20
Remove unused static function from test_TSR.cpp
jslee02 Apr 10, 2017
8f2330f
Set the warning flags for clang as well
jslee02 Apr 10, 2017
2298066
Include gtest include directory to gtest target
jslee02 Apr 10, 2017
b92d42a
Remove unintended empty lines in test_NonColliding.cpp
jslee02 Apr 10, 2017
57c5572
Remove duplicates of warning flags
jslee02 Apr 10, 2017
21fe382
Address more warnings in rviz and planner/ompl
jslee02 Apr 10, 2017
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
1 change: 0 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,6 @@ include(CompilerSettings)
#==============================================================================
# Libraries and unit tests.
#

configure_file(
${CMAKE_MODULE_PATH}/version.hpp.in
${CMAKE_CURRENT_BINARY_DIR}/include/aikido/version.hpp
Expand Down
4 changes: 4 additions & 0 deletions cmake/CompilerSettings.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ if(CMAKE_COMPILER_IS_GNUCXX)

set(AIKIDO_CXX_STANDARD_FLAGS -std=c++11)

add_compile_options(-Wall)
if(TREAT_WARNINGS_AS_ERRORS)
add_compile_options(-Werror)
endif()
Expand All @@ -33,6 +34,7 @@ elseif("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang")

set(AIKIDO_CXX_STANDARD_FLAGS -std=c++11)

add_compile_options(-Wall)
if(TREAT_WARNINGS_AS_ERRORS)
add_compile_options(-Werror)
endif()
Expand All @@ -49,6 +51,7 @@ elseif("${CMAKE_CXX_COMPILER_ID}" STREQUAL "AppleClang")

set(AIKIDO_CXX_STANDARD_FLAGS -std=c++11)

add_compile_options(-Wall)
if(TREAT_WARNINGS_AS_ERRORS)
add_compile_options(-Werror)
endif()
Expand All @@ -64,6 +67,7 @@ elseif(MSVC)
# C++11 (e.g., -std=c++11) since Visual Studio enables it by default when
# available.

add_compile_options(/Wall)
if(TREAT_WARNINGS_AS_ERRORS)
add_compile_options(/WX)
endif()
Expand Down
4 changes: 2 additions & 2 deletions include/aikido/constraint/NewtonsMethodProjectable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@ class NewtonsMethodProjectable : public Projectable

private:
DifferentiablePtr mDifferentiable;
statespace::StateSpacePtr mStateSpace;
int mMaxIteration;
std::vector<double> mTolerance;
int mMaxIteration;
double mMinStepSize;
statespace::StateSpacePtr mStateSpace;

bool contains(const statespace::StateSpace::State* _s) const;
};
Expand Down
2 changes: 1 addition & 1 deletion src/constraint/CartesianProductTestable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ CartesianProductTestable::CartesianProductTestable(
if (!mStateSpace)
throw std::invalid_argument("_stateSpace is nullptr.");

for(int i = 0; i < mConstraints.size(); ++i)
for(size_t i = 0; i < mConstraints.size(); ++i)
{
if (!mConstraints[i])
{
Expand Down
4 changes: 2 additions & 2 deletions src/constraint/FiniteSampleable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ statespace::StateSpacePtr FiniteSampleGenerator::getStateSpace() const
//=============================================================================
bool FiniteSampleGenerator::sample(statespace::StateSpace::State* _state)
{
if (mStates.size() <= mIndex)
if (mStates.size() <= static_cast<size_t>(mIndex))
return false;

mStateSpace->copyState(mStates[mIndex], _state);
Expand All @@ -113,7 +113,7 @@ int FiniteSampleGenerator::getNumSamples() const
//=============================================================================
bool FiniteSampleGenerator::canSample() const
{
return mStates.size() > mIndex;
return mStates.size() > static_cast<size_t>(mIndex);
}

//=============================================================================
Expand Down
1 change: 0 additions & 1 deletion src/constraint/NewtonsMethodProjectable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,6 @@ bool NewtonsMethodProjectable::project(
statespace::StateSpace::State* _out) const
{
using StateSpace = statespace::StateSpace;
using State = StateSpace::State;

int iteration = 0;

Expand Down
41 changes: 21 additions & 20 deletions src/constraint/TSR.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,57 +80,58 @@ class TSRSampleGenerator : public SampleGenerator
//=============================================================================
TSR::TSR(std::unique_ptr<util::RNG> _rng, const Eigen::Isometry3d& _T0_w,
const Eigen::Matrix<double, 6, 2>& _Bw, const Eigen::Isometry3d& _Tw_e)
: mRng(std::move(_rng))
, mStateSpace(std::make_shared<SE3>())
, mT0_w(_T0_w)
: mT0_w(_T0_w)
, mBw(_Bw)
, mTw_e(_Tw_e)
, mRng(std::move(_rng))
, mStateSpace(std::make_shared<SE3>())
{
validate();
}

//=============================================================================
TSR::TSR(const Eigen::Isometry3d& _T0_w, const Eigen::Matrix<double, 6, 2>& _Bw,
const Eigen::Isometry3d& _Tw_e)
: mRng(std::unique_ptr<util::RNG>(
new util::RNGWrapper<std::default_random_engine>(0)))
, mStateSpace(std::make_shared<SE3>())
, mT0_w(_T0_w)
: mT0_w(_T0_w)
, mBw(_Bw)
, mTw_e(_Tw_e)
, mRng(std::unique_ptr<util::RNG>(
new util::RNGWrapper<std::default_random_engine>(0)))
, mStateSpace(std::make_shared<SE3>())
{
validate();
}

//=============================================================================
TSR::TSR(const TSR& other)
: mRng(std::move(other.mRng->clone()))
, mStateSpace(std::make_shared<SE3>())
, mT0_w(other.mT0_w)
, mTw_e(other.mTw_e)
: mT0_w(other.mT0_w)
, mBw(other.mBw)
, mTw_e(other.mTw_e)
, mRng(std::move(other.mRng->clone()))
, mStateSpace(std::make_shared<SE3>())
{
validate();
}

//=============================================================================
TSR::TSR(TSR&& other)
: mRng(std::move(other.mRng))
, mStateSpace(std::make_shared<SE3>())
, mT0_w(other.mT0_w)
, mTw_e(other.mTw_e)
: mT0_w(other.mT0_w)
, mBw(other.mBw)
, mTw_e(other.mTw_e)
, mRng(std::move(other.mRng))
, mStateSpace(std::make_shared<SE3>())
{
validate();
}

//=============================================================================
TSR& TSR::operator=(const TSR& other)
{
mRng = std::move(other.mRng->clone());

mT0_w = other.mT0_w;
mTw_e = other.mTw_e;
mBw = other.mBw;
mTw_e = other.mTw_e;
mRng = std::move(other.mRng->clone());

// Intentionally don't assign StateSpace.

Expand All @@ -140,11 +141,11 @@ TSR& TSR::operator=(const TSR& other)
//=============================================================================
TSR& TSR::operator=(TSR&& other)
{
mRng = std::move(other.mRng);
mStateSpace = std::move(other.mStateSpace);
mT0_w = std::move(other.mT0_w);
mTw_e = std::move(other.mTw_e);
mBw = std::move(other.mBw);
mTw_e = std::move(other.mTw_e);
mRng = std::move(other.mRng);
mStateSpace = std::move(other.mStateSpace);

return *this;
}
Expand Down
12 changes: 6 additions & 6 deletions src/constraint/uniform/RnBoxConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ bool RnBoxConstraintSampleGenerator::sample(
{
Eigen::VectorXd value(mDistributions.size());

for (size_t i = 0; i < value.size(); ++i)
for (int i = 0; i < value.size(); ++i)
value[i] = mDistributions[i](*mRng);

mSpace->setValue(static_cast<statespace::Rn::State*>(_state), value);
Expand Down Expand Up @@ -99,15 +99,15 @@ RnBoxConstraint

const auto dimension = mSpace->getDimension();

if (mLowerLimits.size() != dimension)
if (static_cast<size_t>(mLowerLimits.size()) != dimension)
{
std::stringstream msg;
msg << "Lower limits have incorrect dimension: expected "
<< mSpace->getDimension() << ", got " << mLowerLimits.size() << ".";
throw std::invalid_argument(msg.str());
}

if (mUpperLimits.size() != dimension)
if (static_cast<size_t>(mUpperLimits.size()) != dimension)
{
std::stringstream msg;
msg << "Upper limits have incorrect dimension: expected "
Expand Down Expand Up @@ -154,7 +154,7 @@ bool RnBoxConstraint::isSatisfied(const statespace::StateSpace::State* state) co
const auto value = mSpace->getValue(
static_cast<const statespace::Rn::State*>(state));

for (size_t i = 0; i < value.size(); ++i)
for (int i = 0; i < value.size(); ++i)
{
if (value[i] < mLowerLimits[i] || value[i] > mUpperLimits[i])
return false;
Expand All @@ -170,7 +170,7 @@ bool RnBoxConstraint::project(
Eigen::VectorXd value = mSpace->getValue(
static_cast<const statespace::Rn::State*>(_s));

for (size_t i = 0; i < value.size(); ++i)
for (int i = 0; i < value.size(); ++i)
{
if (value[i] < mLowerLimits[i])
value[i] = mLowerLimits[i];
Expand Down Expand Up @@ -218,7 +218,7 @@ void RnBoxConstraint::getJacobian(
const size_t dimension = mSpace->getDimension();
_out = Eigen::MatrixXd::Zero(dimension, dimension);

for (size_t i = 0; i < _out.rows(); ++i)
for (int i = 0; i < _out.rows(); ++i)
{
if (stateValue[i] < mLowerLimits[i])
_out(i, i) = -1.;
Expand Down
4 changes: 2 additions & 2 deletions src/control/BarrettFingerPositionCommandExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,10 @@ BarrettFingerPositionCommandExecutor::BarrettFingerPositionCommandExecutor(

const auto numDofs = mFinger->getNumDofs();

if (_proximal < numDofs)
if (static_cast<size_t>(_proximal) < numDofs)
mProximalDof = mFinger->getDof(_proximal);

if (_distal < numDofs)
if (static_cast<size_t>(_distal) < numDofs)
mDistalDof = mFinger->getDof(_distal);

if (!mProximalDof)
Expand Down
2 changes: 1 addition & 1 deletion src/control/BarrettFingerSpreadCommandExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ BarrettFingerSpreadCommandExecutor::BarrettFingerSpreadCommandExecutor(
}

const auto numDofs = mFingers[i]->getNumDofs();
if (_spread >= numDofs)
if (static_cast<size_t>(_spread) >= numDofs)
throw std::invalid_argument("Finger does not have spread dof.");

mSpreadDofs.push_back(mFingers[i]->getDof(_spread));
Expand Down
4 changes: 2 additions & 2 deletions src/control/BarrettHandPositionCommandExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ void BarrettHandPositionCommandExecutor::step(double _timeSincePreviousCall)
std::exception_ptr expr;
bool allFingersCompleted = true;

for(int i = 0; i < mFingerFutures.size(); ++i)
for(size_t i = 0; i < mFingerFutures.size(); ++i)
{
// Check the status of each finger
auto status = mFingerFutures[i].wait_for(kWaitPeriod);
Expand All @@ -92,7 +92,7 @@ void BarrettHandPositionCommandExecutor::step(double _timeSincePreviousCall)

if (allFingersCompleted)
{
for(int i = 0; i < mFingerFutures.size(); ++i)
for(size_t i = 0; i < mFingerFutures.size(); ++i)
{
try{
mFingerFutures[i].get();
Expand Down
6 changes: 4 additions & 2 deletions src/control/KinematicSimulationTrajectoryExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,13 @@ KinematicSimulationTrajectoryExecutor::KinematicSimulationTrajectoryExecutor(
::dart::dynamics::SkeletonPtr _skeleton,
std::chrono::milliseconds _period)
: mSkeleton(std::move(_skeleton))
, mSpinMutex()
, mRunning(true)
, mPromise(nullptr)
, mTraj(nullptr)
, mPeriod(_period)
, mSpinMutex()
, mRunning(true)


{
using std::chrono::duration;
using std::chrono::duration_cast;
Expand Down
1 change: 1 addition & 0 deletions src/external/hauser_parabolic_smoother/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,4 +11,5 @@ set_target_properties("${PROJECT_NAME}_external_hauserparabolicsmoother"
)
target_compile_options("${PROJECT_NAME}_external_hauserparabolicsmoother"
PUBLIC ${AIKIDO_CXX_STANDARD_FLAGS}
PRIVATE -w
Copy link
Member

Choose a reason for hiding this comment

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

What is this? 😱

Copy link
Member

Choose a reason for hiding this comment

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

If I'm correct, this is to ignore warnings from ${PROJECT_NAME}_external_hauserparabolicsmoother target. Since it's not an external target, we cannot use include_directories() with SYSTEM option.

)
2 changes: 1 addition & 1 deletion src/external/hauser_parabolic_smoother/DynamicPath.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ void DynamicPath::SetMilestones(const vector<Vector>& x)
ramps[i].x1 = x[i+1];
ramps[i].dx0 = zero;
ramps[i].dx1 = zero;
bool res=ramps[i].SolveMinTimeLinear(accMax,velMax);
bool res = ramps[i].SolveMinTimeLinear(accMax,velMax);
PARABOLIC_RAMP_ASSERT(res);
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/external/hauser_parabolic_smoother/ParabolicRamp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ void TestRamps(const char* fn)
while(LoadRamp(f,ramp.x0,ramp.dx0,ramp.x1,ramp.dx1,a,v,t)) {
if(t < 0) {
PARABOLIC_RAMP_ASSERT( a >= 0 && v >= 0);
bool res=ramp.SolveMinTime(a,v);
bool res = ramp.SolveMinTime(a,v);
PARABOLIC_RAMP_PLOG("Result %d: t=%g\n",(int)res,ramp.ttotal);
}
else if(a < 0) {
Expand Down
6 changes: 3 additions & 3 deletions src/planner/parabolic/ParabolicTimer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ ParabolicRamp::Vector toVector(const Eigen::VectorXd& _x)
{
ParabolicRamp::Vector output(_x.size());

for (size_t i = 0; i < _x.size(); ++i)
for (int i = 0; i < _x.size(); ++i)
output[i] = _x[i];

return output;
Expand Down Expand Up @@ -101,10 +101,10 @@ std::unique_ptr<trajectory::Spline> computeParabolicTiming(
if (numWaypoints == 0)
throw std::invalid_argument("Trajectory is empty.");

if (_maxVelocity.size() != dimension)
if (static_cast<size_t>(_maxVelocity.size()) != dimension)
throw std::invalid_argument("Velocity limits have wrong dimension.");

if (_maxAcceleration.size() != dimension)
if (static_cast<size_t>(_maxAcceleration.size()) != dimension)
throw std::invalid_argument("Acceleration limits have wrong dimension.");

for (size_t i = 0; i < dimension; ++i)
Expand Down
4 changes: 2 additions & 2 deletions src/statespace/CartesianProduct.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ void CartesianProduct::expMap(const Eigen::VectorXd &_tangent,
auto dimension = getDimension();

// TODO: Skip these checks in release mode.
if (_tangent.rows() != dimension) {
if (static_cast<size_t>(_tangent.rows()) != dimension) {
std::stringstream msg;
msg << "_tangent has incorrect size: expected " << dimension << ", got "
<< _tangent.rows() << ".\n";
Expand All @@ -156,7 +156,7 @@ void CartesianProduct::logMap(const StateSpace::State *_in,
{
auto dimension = getDimension();

if (_tangent.rows() != dimension) {
if (static_cast<size_t>(_tangent.rows()) != dimension) {
_tangent.resize(dimension);
}

Expand Down
4 changes: 2 additions & 2 deletions src/statespace/dart/MetaSkeletonStateSpace.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ MetaSkeletonPtr MetaSkeletonStateSpace::getMetaSkeleton() const
void MetaSkeletonStateSpace::convertPositionsToState(
const Eigen::VectorXd& _positions, State* _state) const
{
if (_positions.size() != mMetaSkeleton->getNumDofs())
if (static_cast<size_t>(_positions.size()) != mMetaSkeleton->getNumDofs())
throw std::invalid_argument("Incorrect number of positions.");

for (size_t isubspace = 0; isubspace < getNumSubspaces(); ++isubspace)
Expand Down Expand Up @@ -149,7 +149,7 @@ void MetaSkeletonStateSpace::convertStateToPositions(
subspace->convertStateToPositions(substate, jointPositions);

// TODO: Find a more efficient way to do this mapping.
for (size_t idof = 0; idof < jointPositions.size(); ++idof)
for (size_t idof = 0; idof < static_cast<size_t>(jointPositions.size()); ++idof)
{
const auto dof = joint->getDof(idof);
const auto dofIndex = mMetaSkeleton->getIndexOf(dof, false);
Expand Down
5 changes: 3 additions & 2 deletions src/statespace/dart/SE2Joint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,9 @@ namespace dart {

//=============================================================================
SE2Joint::SE2Joint(::dart::dynamics::PlanarJoint* _joint)
: JointStateSpace(_joint)
, SE2()
: SE2()
, JointStateSpace(_joint)

Copy link
Member

Choose a reason for hiding this comment

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

Nit: Remove unnecessary empty line

{
}

Expand Down
4 changes: 2 additions & 2 deletions src/statespace/dart/SE3Joint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@ namespace dart {

//=============================================================================
SE3Joint::SE3Joint(::dart::dynamics::FreeJoint* _joint)
: JointStateSpace(_joint)
, SE3()
: SE3()
, JointStateSpace(_joint)
{
}

Expand Down
Loading