Skip to content

Commit 69c756e

Browse files
committed
Merge branch 'master' into francofusco-segments-removal
2 parents f591582 + b35c424 commit 69c756e

37 files changed

+530
-414
lines changed

.travis.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@ env:
99

1010
before_script:
1111
- sudo apt-get -qq update
12-
- sudo apt-get install -y libeigen3-dev libcppunit-dev python-sip-dev
12+
- sudo apt-get install -y libeigen3-dev libcppunit-dev python-sip-dev python-psutil
1313
#build orocos_kdl
1414
- cd orocos_kdl
1515
- mkdir build

orocos_kdl/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,9 @@
22
# Test CMake version
33
#
44
CMAKE_MINIMUM_REQUIRED(VERSION 2.6)
5+
IF(POLICY CMP0048)
6+
CMAKE_POLICY(SET CMP0048 NEW)
7+
ENDIF()
58
#MARK_AS_ADVANCED( FORCE CMAKE_BACKWARDS_COMPATIBILITY )
69

710

orocos_kdl/src/chainfdsolver_recursive_newton_euler.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -70,64 +70,64 @@ namespace KDL{
7070
return (error);
7171

7272
// Calculate non-inertial internal torques by inputting zero joint acceleration to ID
73-
for(int i=0;i<nj;i++){
73+
for(unsigned int i=0;i<nj;i++){
7474
q_dotdot(i) = 0.;
7575
}
7676
error = IdSolver.CartToJnt(q, q_dot, q_dotdot, f_ext, Tzeroacc);
7777
if (error < 0)
7878
return (error);
7979

8080
// Calculate acceleration using inverse symmetric matrix times vector
81-
for(int i=0;i<nj;i++){
81+
for(unsigned int i=0;i<nj;i++){
8282
Tzeroacc_eig(i) = (torques(i)-Tzeroacc(i));
83-
for(int j=0;j<nj;j++){
83+
for(unsigned int j=0;j<nj;j++){
8484
H_eig(i,j) = H(i,j);
8585
}
8686
}
8787
ldl_solver_eigen(H_eig, Tzeroacc_eig, L_eig, D_eig, r_eig, acc_eig);
88-
for(int i=0;i<nj;i++){
88+
for(unsigned int i=0;i<nj;i++){
8989
q_dotdot(i) = acc_eig(i);
9090
}
9191

9292
return (error = E_NOERROR);
9393
}
9494

95-
void ChainFdSolver_RNE::RK4Integrator(int& nj, const double& t, double& dt, KDL::JntArray& q, KDL::JntArray& q_dot,
95+
void ChainFdSolver_RNE::RK4Integrator(unsigned int& nj, const double& t, double& dt, KDL::JntArray& q, KDL::JntArray& q_dot,
9696
KDL::JntArray& torques, KDL::Wrenches& f_ext, KDL::ChainFdSolver_RNE& fdsolver,
9797
KDL::JntArray& q_dotdot, KDL::JntArray& dq, KDL::JntArray& dq_dot,
9898
KDL::JntArray& q_temp, KDL::JntArray& q_dot_temp)
9999
{
100100
fdsolver.CartToJnt(q, q_dot, torques, f_ext, q_dotdot);
101-
for (int i=0; i<nj; ++i)
101+
for (unsigned int i=0; i<nj; ++i)
102102
{
103103
q_temp(i) = q(i) + q_dot(i)*dt/2.0;
104104
q_dot_temp(i) = q_dot(i) + q_dotdot(i)*dt/2.0;
105105
dq(i) = q_dot(i);
106106
dq_dot(i) = q_dotdot(i);
107107
}
108108
fdsolver.CartToJnt(q_temp, q_dot_temp, torques, f_ext, q_dotdot);
109-
for (int i=0; i<nj; ++i)
109+
for (unsigned int i=0; i<nj; ++i)
110110
{
111111
q_temp(i) = q(i) + q_dot_temp(i)*dt/2.0;
112112
q_dot_temp(i) = q_dot(i) + q_dotdot(i)*dt/2.0;
113113
dq(i) += 2.0*q_dot_temp(i);
114114
dq_dot(i) += 2.0*q_dotdot(i);
115115
}
116116
fdsolver.CartToJnt(q_temp, q_dot_temp, torques, f_ext, q_dotdot);
117-
for (int i=0; i<nj; ++i)
117+
for (unsigned int i=0; i<nj; ++i)
118118
{
119119
q_temp(i) = q(i) + q_dot_temp(i)*dt;
120120
q_dot_temp(i) = q_dot(i) + q_dotdot(i)*dt;
121121
dq(i) += 2.0*q_dot_temp(i);
122122
dq_dot(i) += 2.0*q_dotdot(i);
123123
}
124124
fdsolver.CartToJnt(q_temp, q_dot_temp, torques, f_ext, q_dotdot);
125-
for (int i=0; i<nj; ++i)
125+
for (unsigned int i=0; i<nj; ++i)
126126
{
127127
dq(i) = (dq(i)+q_dot_temp(i))*dt/6.0;
128128
dq_dot(i) = (dq_dot(i)+q_dotdot(i))*dt/6.0;
129129
}
130-
for (int i=0; i<nj; ++i)
130+
for (unsigned int i=0; i<nj; ++i)
131131
{
132132
q(i) += dq(i);
133133
q_dot(i) += dq_dot(i);

orocos_kdl/src/chainfdsolver_recursive_newton_euler.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ namespace KDL{
8686
* \param qtemp Intermediate joint positions
8787
* \param qdtemp Intermediate joint velocities
8888
*/
89-
void RK4Integrator(int& nj, const double& t, double& dt, KDL::JntArray& q, KDL::JntArray& q_dot,
89+
void RK4Integrator(unsigned int& nj, const double& t, double& dt, KDL::JntArray& q, KDL::JntArray& q_dot,
9090
KDL::JntArray& torques, KDL::Wrenches& f_ext, KDL::ChainFdSolver_RNE& fdsolver,
9191
KDL::JntArray& q_dotdot, KDL::JntArray& dq, KDL::JntArray& dq_dot,
9292
KDL::JntArray& q_temp, KDL::JntArray& q_dot_temp);
@@ -97,8 +97,8 @@ namespace KDL{
9797
ChainIdSolver_RNE IdSolver;
9898
unsigned int nj;
9999
unsigned int ns;
100-
JntArray Tzeroacc;
101100
JntSpaceInertiaMatrix H;
101+
JntArray Tzeroacc;
102102
Eigen::MatrixXd H_eig;
103103
Eigen::VectorXd Tzeroacc_eig;
104104
Eigen::MatrixXd L_eig;

orocos_kdl/src/chainiksolverpos_lma.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -321,4 +321,4 @@ const char* ChainIkSolverPos_LMA::strError(const int error) const
321321
else return SolverI::strError(error);
322322
}
323323

324-
};//namespace KDL
324+
}//namespace KDL

orocos_kdl/src/chainiksolverpos_lma.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -246,7 +246,7 @@ class ChainIkSolverPos_LMA : public KDL::ChainIkSolverPos
246246

247247

248248

249-
}; // namespace KDL
249+
} // namespace KDL
250250

251251

252252

orocos_kdl/src/chainiksolvervel_pinv.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@ namespace KDL
7777
* not (yet) implemented.
7878
*
7979
*/
80-
virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out){return -1;};
80+
virtual int CartToJnt(const JntArray& /*q_init*/, const FrameVel& /*v_in*/, JntArrayVel& /*q_out*/){return -1;};
8181

8282
/**
8383
* Retrieve the number of singular values of the jacobian that are < eps;

orocos_kdl/src/chainiksolvervel_pinv_givens.cpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,6 @@ namespace KDL
3838
B(m,n),
3939
S(n),
4040
tempi(m),
41-
tempj(m),
4241
UY(VectorXd::Zero(6)),
4342
SUY(VectorXd::Zero(nj)),
4443
qdot_eigen(nj),
@@ -59,7 +58,6 @@ namespace KDL
5958
B.conservativeResize(m,n);
6059
S.conservativeResize(n);
6160
tempi.conservativeResize(m);
62-
tempj.conservativeResize(n);
6361
SUY.conservativeResizeLike(VectorXd::Zero(nj));
6462
qdot_eigen.conservativeResize(nj);
6563
}

orocos_kdl/src/chainiksolvervel_pinv_givens.hpp

Lines changed: 2 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -30,10 +30,6 @@ namespace KDL
3030
*
3131
* @param chain the chain to calculate the inverse velocity
3232
* kinematics for
33-
* @param eps if a singular value is below this value, its
34-
* inverse is set to zero, default: 0.00001
35-
* @param maxiter maximum iterations for the svd calculation,
36-
* default: 150
3733
*
3834
*/
3935
explicit ChainIkSolverVel_pinv_givens(const Chain& chain);
@@ -44,7 +40,7 @@ namespace KDL
4440
* not (yet) implemented.
4541
*
4642
*/
47-
virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out){return (error = E_NOT_IMPLEMENTED);};
43+
virtual int CartToJnt(const JntArray& /*q_init*/, const FrameVel& /*v_in*/, JntArrayVel& /*q_out*/){return (error = E_NOT_IMPLEMENTED);};
4844

4945
/// @copydoc KDL::SolverI::updateInternalDataStructures
5046
virtual void updateInternalDataStructures();
@@ -57,7 +53,7 @@ namespace KDL
5753
bool transpose,toggle;
5854
unsigned int m,n;
5955
MatrixXd jac_eigen,U,V,B;
60-
VectorXd S,tempi,tempj,UY,SUY,qdot_eigen,v_in_eigen;
56+
VectorXd S,tempi,UY,SUY,qdot_eigen,v_in_eigen;
6157
};
6258
}
6359
#endif

orocos_kdl/src/chainiksolvervel_pinv_nso.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,7 @@ namespace KDL
6969
* not (yet) implemented.
7070
*
7171
*/
72-
virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out){return -1;};
72+
virtual int CartToJnt(const JntArray& /*q_init*/, const FrameVel& /*v_in*/, JntArrayVel& /*q_out*/){return -1;};
7373

7474
/**
7575
* Request the joint weights for optimization criterion

0 commit comments

Comments
 (0)