Skip to content

Commit 6dc4913

Browse files
committed
[Marginal] Removing warning signed vs unsigned
1 parent 144d9c2 commit 6dc4913

File tree

8 files changed

+34
-34
lines changed

8 files changed

+34
-34
lines changed

benchmark/timings.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ int main(int argc, const char ** argv)
2727
using namespace se3;
2828

2929
StackTicToc timer(StackTicToc::US);
30-
const int NBT = 1000*100;
30+
const size_t NBT = 1000*100;
3131
se3::Model model;
3232

3333
std::string filename = PINOCCHIO_SOURCE_DIR"/models/simple_humanoid.urdf";

src/multibody/model.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -290,7 +290,7 @@ namespace se3
290290

291291
const std::string& Model::getBodyName( Model::Index index ) const
292292
{
293-
assert( (index>=0)&&(index < (Model::Index)nbody) );
293+
assert( index < (Model::Index)nbody );
294294
return names[index];
295295
}
296296

unittest/cholesky.cpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -124,12 +124,12 @@ BOOST_AUTO_TEST_CASE ( test_timings )
124124
StackTicToc timer(StackTicToc::US);
125125
#ifdef NDEBUG
126126
#ifdef _INTENSE_TESTING_
127-
const int NBT = 1000*1000;
127+
const size_t NBT = 1000*1000;
128128
#else
129-
const int NBT = 10;
129+
const size_t NBT = 10;
130130
#endif
131131
#else
132-
const int NBT = 1;
132+
const size_t NBT = 1;
133133
std::cout << "(the time score in debug mode is not relevant) " ;
134134
#endif
135135

@@ -164,7 +164,7 @@ BOOST_AUTO_TEST_CASE ( test_timings )
164164
if( flag >> 2 & 31 )
165165
{
166166
std::vector<Eigen::VectorXd> randvec(NBT);
167-
for(int i=0;i<NBT;++i ) randvec[(std::size_t)i] = Eigen::VectorXd::Random(model.nv);
167+
for(size_t i=0;i<NBT;++i ) randvec[i] = Eigen::VectorXd::Random(model.nv);
168168
Eigen::VectorXd zero = Eigen::VectorXd(model.nv);
169169
Eigen::VectorXd res (model.nv);
170170

@@ -174,7 +174,7 @@ BOOST_AUTO_TEST_CASE ( test_timings )
174174
timer.tic();
175175
SMOOTH(NBT)
176176
{
177-
se3::cholesky::solve(model,data,randvec[(std::size_t)_smooth]);
177+
se3::cholesky::solve(model,data,randvec[_smooth]);
178178
}
179179
if(verbose) std::cout << "solve =\t\t";
180180
timer.toc(std::cout,NBT);
@@ -185,7 +185,7 @@ BOOST_AUTO_TEST_CASE ( test_timings )
185185
timer.tic();
186186
SMOOTH(NBT)
187187
{
188-
se3::cholesky::Uv(model,data,randvec[(std::size_t)_smooth]);
188+
se3::cholesky::Uv(model,data,randvec[_smooth]);
189189
}
190190
if(verbose) std::cout << "Uv =\t\t";
191191
timer.toc(std::cout,NBT);
@@ -196,7 +196,7 @@ BOOST_AUTO_TEST_CASE ( test_timings )
196196
timer.tic();
197197
SMOOTH(NBT)
198198
{
199-
se3::cholesky::Uiv(model,data,randvec[(std::size_t)_smooth]);
199+
se3::cholesky::Uiv(model,data,randvec[_smooth]);
200200
}
201201
if(verbose) std::cout << "Uiv =\t\t";
202202
timer.toc(std::cout,NBT);
@@ -207,7 +207,7 @@ BOOST_AUTO_TEST_CASE ( test_timings )
207207
Eigen::VectorXd res;
208208
SMOOTH(NBT)
209209
{
210-
res = se3::cholesky::Mv(model,data,randvec[(std::size_t)_smooth]);
210+
res = se3::cholesky::Mv(model,data,randvec[_smooth]);
211211
}
212212
if(verbose) std::cout << "Mv =\t\t";
213213
timer.toc(std::cout,NBT);
@@ -217,7 +217,7 @@ BOOST_AUTO_TEST_CASE ( test_timings )
217217
timer.tic();
218218
SMOOTH(NBT)
219219
{
220-
se3::cholesky::Mv(model,data,randvec[(std::size_t)_smooth],true);
220+
se3::cholesky::Mv(model,data,randvec[_smooth],true);
221221
}
222222
if(verbose) std::cout << "UDUtv =\t\t";
223223
timer.toc(std::cout,NBT);

unittest/com.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -92,12 +92,12 @@ BOOST_AUTO_TEST_CASE ( test_com )
9292
// StackTicToc timer(StackTicToc::US);
9393
// #ifdef NDEBUG
9494
// #ifdef _INTENSE_TESTING_
95-
// const int NBT = 1000*1000;
95+
// const size_t NBT = 1000*1000;
9696
// #else
97-
// const int NBT = 10;
97+
// const size_t NBT = 10;
9898
// #endif
9999
// #else
100-
// const int NBT = 1;
100+
// const size_t NBT = 1;
101101
// std::cout << "(the time score in debug mode is not relevant) " ;
102102
// #endif
103103
//

unittest/crba.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -47,9 +47,9 @@ BOOST_AUTO_TEST_CASE ( test_crba )
4747

4848
#ifdef NDEBUG
4949
#ifdef _INTENSE_TESTING_
50-
const int NBT = 1000*1000;
50+
const size_t NBT = 1000*1000;
5151
#else
52-
const int NBT = 10;
52+
const size_t NBT = 10;
5353
#endif
5454

5555
Eigen::VectorXd q = Eigen::VectorXd::Zero(model.nq);
@@ -62,7 +62,7 @@ BOOST_AUTO_TEST_CASE ( test_crba )
6262
timer.toc(std::cout,NBT);
6363

6464
#else
65-
int NBT = 1;
65+
const size_t NBT = 1;
6666
using namespace Eigen;
6767
using namespace se3;
6868

unittest/jacobian.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -52,15 +52,15 @@ BOOST_AUTO_TEST_CASE ( test_jacobian )
5252
VectorXd qdot = VectorXd::Random(model.nv);
5353
VectorXd qddot = VectorXd::Zero(model.nv);
5454
rnea( model,data,q,qdot,qddot );
55-
Motion v = data.oMi[(std::size_t)idx].act( data.v[(std::size_t)idx] );
55+
Motion v = data.oMi[idx].act( data.v[idx] );
5656
is_matrix_absolutely_closed(v.toVector(),Jrh*qdot,1e-12);
5757

5858

5959
/* Test local jacobian: rhJrh == rhXo oJrh */
6060
MatrixXd rhJrh(6,model.nv); rhJrh.fill(0);
6161
getJacobian<true>(model,data,idx,rhJrh);
6262
MatrixXd XJrh(6,model.nv);
63-
motionSet::se3Action( data.oMi[(std::size_t)idx].inverse(), Jrh,XJrh );
63+
motionSet::se3Action( data.oMi[idx].inverse(), Jrh,XJrh );
6464
is_matrix_absolutely_closed(XJrh,rhJrh,1e-12);
6565

6666

@@ -84,12 +84,12 @@ BOOST_AUTO_TEST_CASE ( test_timings )
8484
StackTicToc timer(StackTicToc::US);
8585
#ifdef NDEBUG
8686
#ifdef _INTENSE_TESTING_
87-
const int NBT = 1000*1000;
87+
const size_t NBT = 1000*1000;
8888
#else
89-
const int NBT = 10;
89+
const size_t NBT = 10;
9090
#endif
9191
#else
92-
const int NBT = 1;
92+
const size_t NBT = 1;
9393
std::cout << "(the time score in debug mode is not relevant) " ;
9494
#endif
9595

unittest/rnea.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -67,9 +67,9 @@ BOOST_AUTO_TEST_CASE ( test_rnea )
6767
VectorXd a = VectorXd::Random(model.nv);
6868

6969
#ifdef NDEBUG
70-
int NBT = 10000;
70+
const size_t NBT = 10000;
7171
#else
72-
int NBT = 1;
72+
const size_t NBT = 1;
7373
std::cout << "(the time score in debug mode is not relevant) " ;
7474
#endif
7575

unittest/symmetric.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -209,19 +209,19 @@ BOOST_AUTO_TEST_CASE ( test_pinocchio_Sym3 )
209209

210210
// Time test
211211
{
212-
const int NBT = 100000;
212+
const size_t NBT = 100000;
213213
Symmetric3 S = Symmetric3::RandomPositive();
214214

215215
std::vector<Symmetric3> Sres (NBT);
216216
std::vector<Matrix3> Rs (NBT);
217-
for(int i=0;i<NBT;++i)
218-
Rs[(std::size_t)i] = (Eigen::Quaterniond(Eigen::Matrix<double,4,1>::Random())).normalized().matrix();
217+
for(size_t i=0;i<NBT;++i)
218+
Rs[i] = (Eigen::Quaterniond(Eigen::Matrix<double,4,1>::Random())).normalized().matrix();
219219

220220
std::cout << "Pinocchio: ";
221221
StackTicToc timer(StackTicToc::US); timer.tic();
222222
SMOOTH(NBT)
223223
{
224-
timeSym3(S,Rs[(std::size_t)_smooth],Sres[(std::size_t)_smooth]);
224+
timeSym3(S,Rs[_smooth],Sres[_smooth]);
225225
}
226226
timer.toc(std::cout,NBT);
227227
}
@@ -249,10 +249,10 @@ BOOST_AUTO_TEST_CASE ( test_metapod_LTI )
249249
timeLTI(S,R,S2);
250250
is_matrix_absolutely_closed(S2.toMatrix(), R.toMatrix().transpose()*S.toMatrix()*R.toMatrix(), 1e-12);
251251

252-
const int NBT = 100000;
252+
const size_t NBT = 100000;
253253
std::vector<Sym3> Sres (NBT);
254254
std::vector<R3> Rs (NBT);
255-
for(int i=0;i<NBT;++i)
255+
for(size_t i=0;i<NBT;++i)
256256
Rs[i].randomInit();
257257

258258
std::cout << "Metapod: ";
@@ -297,17 +297,17 @@ BOOST_AUTO_TEST_CASE ( test_eigen_SelfAdj )
297297
is_matrix_absolutely_closed(Masa1, Masa2, 1e-16);
298298
}
299299

300-
const int NBT = 100000;
300+
const size_t NBT = 100000;
301301
std::vector<Eigen::Matrix3d> Sres (NBT);
302302
std::vector<Eigen::Matrix3d> Rs (NBT);
303-
for(int i=0;i<NBT;++i)
304-
Rs[(std::size_t)i] = (Eigen::Quaterniond(Eigen::Matrix<double,4,1>::Random())).normalized().matrix();
303+
for(size_t i=0;i<NBT;++i)
304+
Rs[i] = (Eigen::Quaterniond(Eigen::Matrix<double,4,1>::Random())).normalized().matrix();
305305

306306
std::cout << "Eigen: ";
307307
StackTicToc timer(StackTicToc::US); timer.tic();
308308
SMOOTH(NBT)
309309
{
310-
timeSelfAdj(Rs[(std::size_t)_smooth],M,Sres[(std::size_t)_smooth]);
310+
timeSelfAdj(Rs[_smooth],M,Sres[_smooth]);
311311
}
312312
timer.toc(std::cout,NBT);
313313
}

0 commit comments

Comments
 (0)