Commit 698f692f authored by Guilhem Saurel's avatar Guilhem Saurel
Browse files

fix warnings

parent 30f3f35a
......@@ -19,7 +19,7 @@ IF(BUILD_PYTHON_INTERFACE)
FINDPYTHON()
INCLUDE_DIRECTORIES(${PYTHON_INCLUDE_DIRS})
ADD_REQUIRED_DEPENDENCY("eigenpy")
ADD_REQUIRED_DEPENDENCY("eigenpy >= 1.4.0")
FIND_PACKAGE(Boost COMPONENTS python REQUIRED )
INCLUDE_DIRECTORIES(SYSTEM ${Boost_INCLUDE_DIR})
......@@ -43,7 +43,7 @@ IF(CLP_FOUND)
INCLUDE_DIRECTORIES("${CLP_INCLUDE_DIR}")
ENDIF()
INCLUDE_DIRECTORIES(${qpOASES_INCLUDE_DIRS})
INCLUDE_DIRECTORIES(SYSTEM ${qpOASES_INCLUDE_DIRS})
ADD_SUBDIRECTORY(include/${CUSTOM_HEADER_DIR})
ADD_SUBDIRECTORY(src)
......
......@@ -63,10 +63,10 @@ BOOST_PYTHON_MODULE(hpp_centroidal_dynamics)
/** BEGIN eigenpy init**/
eigenpy::enableEigenPy();
eigenpy::enableEigenPySpecific<MatrixX3ColMajor,MatrixX3ColMajor>();
eigenpy::enableEigenPySpecific<MatrixXXColMajor,MatrixXXColMajor>();
eigenpy::enableEigenPySpecific<Vector3,Vector3>();
eigenpy::enableEigenPySpecific<VectorX,VectorX>();
eigenpy::enableEigenPySpecific<MatrixX3ColMajor>();
eigenpy::enableEigenPySpecific<MatrixXXColMajor>();
eigenpy::enableEigenPySpecific<Vector3>();
eigenpy::enableEigenPySpecific<VectorX>();
/*eigenpy::exposeAngleAxis();
eigenpy::exposeQuaternion();*/
......
......@@ -21,12 +21,12 @@ bool Equilibrium::m_is_cdd_initialized = false;
Equilibrium::Equilibrium(const Equilibrium& other)
: m_mass(other.m_mass)
, m_gravity(other.m_gravity)
, m_G_centr(other.m_G_centr)
, m_name (other.m_name)
, m_algorithm(other.m_algorithm)
, m_solver_type (other.m_solver_type)
, m_solver (Solver_LP_abstract::getNewSolver(other.m_solver_type))
, m_generatorsPerContact(other.m_generatorsPerContact)
, m_G_centr(other.m_G_centr)
, m_H(other.m_H)
, m_h(other.m_h)
, m_is_cdd_stable(other.m_is_cdd_stable)
......@@ -129,7 +129,7 @@ bool Equilibrium::computeGenerators(Cref_matrixX3 contactPoints, Cref_matrixX3 c
// compute generators
theta = pi_4;
for(int j=0; j<cg; j++)
for(unsigned int j=0; j<cg; j++)
{
G.col(j) = frictionCoefficient*sin(theta)*T1
+ frictionCoefficient*cos(theta)*T2
......@@ -145,7 +145,7 @@ bool Equilibrium::computeGenerators(Cref_matrixX3 contactPoints, Cref_matrixX3 c
// Compute the coefficient to convert b0 to e_max
Vector3 f0 = Vector3::Zero();
for(int j=0; j<cg; j++)
for(unsigned int j=0; j<cg; j++)
f0 += G.col(j); // sum of the contact generators
// Compute the distance between the friction cone boundaries and
// the sum of the contact generators, which is e_max when b0=1.
......@@ -204,7 +204,7 @@ bool Equilibrium::setNewContacts(const MatrixX3& contactPoints, const MatrixX3&
attempts--;
}
// resetting random because obviously libcdd always resets to 0
srand(time(NULL));
srand((unsigned int)time(NULL));
if(!m_is_cdd_stable)
{
return false;
......@@ -356,7 +356,7 @@ LP_status Equilibrium::computeEquilibriumRobustness(Cref_vector3 com, Cref_vecto
}
LP_status Equilibrium::checkRobustEquilibrium(Cref_vector3 com, bool &equilibrium, double e_max){
checkRobustEquilibrium(com,zero_acc,equilibrium,e_max);
return checkRobustEquilibrium(com,zero_acc,equilibrium,e_max);
}
LP_status Equilibrium::checkRobustEquilibrium(Cref_vector3 com, Cref_vector3 acc, bool &equilibrium, double e_max)
......@@ -547,7 +547,7 @@ LP_status Equilibrium::findExtremumOverLine(Cref_vector3 a, Cref_vector3 a0, dou
return LP_STATUS_ERROR;
}
LP_status Equilibrium::findExtremumInDirection(Cref_vector3 direction, Ref_vector3 com, double e_max)
LP_status Equilibrium::findExtremumInDirection(__attribute__((unused)) Cref_vector3 direction, __attribute__((unused)) Ref_vector3 com, __attribute__((unused)) double e_max)
{
if(m_G_centr.cols()==0)
return LP_STATUS_INFEASIBLE;
......
......@@ -44,14 +44,14 @@ bool Solver_LP_abstract::writeLpToFile(const std::string& filename,
assert(Aub.size()==m);
std::ofstream out(filename.c_str(), std::ios::out | std::ios::binary | std::ios::trunc);
out.write((char*) (&n), sizeof(typename MatrixXX::Index));
out.write((char*) (&m), sizeof(typename MatrixXX::Index));
out.write((char*) c.data(), n*sizeof(typename MatrixXX::Scalar) );
out.write((char*) lb.data(), n*sizeof(typename MatrixXX::Scalar) );
out.write((char*) ub.data(), n*sizeof(typename MatrixXX::Scalar) );
out.write((char*) A.data(), m*n*sizeof(typename MatrixXX::Scalar) );
out.write((char*) Alb.data(), m*sizeof(typename MatrixXX::Scalar) );
out.write((char*) Aub.data(), m*sizeof(typename MatrixXX::Scalar) );
out.write((const char*) (&n), sizeof(typename MatrixXX::Index));
out.write((const char*) (&m), sizeof(typename MatrixXX::Index));
out.write((const char*) c.data(), n*sizeof(typename MatrixXX::Scalar) );
out.write((const char*) lb.data(), n*sizeof(typename MatrixXX::Scalar) );
out.write((const char*) ub.data(), n*sizeof(typename MatrixXX::Scalar) );
out.write((const char*) A.data(), m*n*sizeof(typename MatrixXX::Scalar) );
out.write((const char*) Alb.data(), m*sizeof(typename MatrixXX::Scalar) );
out.write((const char*) Aub.data(), m*sizeof(typename MatrixXX::Scalar) );
out.close();
return true;
}
......
......@@ -245,7 +245,7 @@ void Stopwatch::report(string perf_name, int precision, std::ostream& output)
const int MAX_NAME_LENGTH = 60;
string pad = "";
for (int i = perf_name.length(); i<MAX_NAME_LENGTH; i++)
for (unsigned long i = perf_name.length(); i<MAX_NAME_LENGTH; i++)
pad.append(" ");
output << perf_name << pad;
......
......@@ -160,7 +160,7 @@ int test_computeEquilibriumRobustness(Equilibrium *solver_1, Equilibrium *solver
* @param verb Verbosity level, 0 print nothing, 1 print summary, 2 print everything
*/
int test_findExtremumOverLine(Equilibrium *solver_to_test, Equilibrium *solver_ground_truth,
Cref_vector3 a0, int N_TESTS, double e_max,
Cref_vector3 a0, unsigned int N_TESTS, double e_max,
const string& PERF_STRING_TEST, const string& PERF_STRING_GROUND_TRUTH, int verb=0)
{
int error_counter = 0;
......@@ -230,7 +230,7 @@ int test_findExtremumOverLine(Equilibrium *solver_to_test, Equilibrium *solver_g
* @param solver The solver to use for computing the equilibrium robustness.
* @param comPositions Grid of CoM positions in the form of an Nx2 matrix.
*/
void drawRobustnessGrid(int N_CONTACTS, int GRID_SIZE, Equilibrium *solver,
void drawRobustnessGrid(unsigned int N_CONTACTS, unsigned int GRID_SIZE, Equilibrium *solver,
Cref_matrixXX comPositions, Cref_matrixXX p)
{
MatrixXi contactPointCoord(4*N_CONTACTS,2);
......@@ -262,9 +262,9 @@ void drawRobustnessGrid(int N_CONTACTS, int GRID_SIZE, Equilibrium *solver,
for(unsigned int j=0; j<GRID_SIZE; j++)
{
contactPointDrawn = false;
for(long k=0; k<4*N_CONTACTS; k++)
for(unsigned long k=0; k<4*N_CONTACTS; k++)
{
if(contactPointCoord(k,0)==i && contactPointCoord(k,1)==j)
if((unsigned) contactPointCoord(k,0)== i && (unsigned) contactPointCoord(k,1)==j)
{
cout<<"X ";
contactPointDrawn = true;
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment