Skip to content

Commit 3c85f21

Browse files
committed
Fix unused-parameter
1 parent c92d084 commit 3c85f21

15 files changed

+26
-34
lines changed

orocos_kdl/src/chainfdsolver_recursive_newton_euler.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ namespace KDL{
9292
return (error = E_NOERROR);
9393
}
9494

95-
void ChainFdSolver_RNE::RK4Integrator(unsigned 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)

orocos_kdl/src/chainhdsolver_vereshchagin.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ int ChainHdSolver_Vereshchagin::CartToJnt(const JntArray &q, const JntArray &q_d
7474
return (error = E_NOERROR);
7575
}
7676

77-
void ChainHdSolver_Vereshchagin::initial_upwards_sweep(const JntArray &q, const JntArray &qdot, const JntArray &qdotdot, const Wrenches& f_ext)
77+
void ChainHdSolver_Vereshchagin::initial_upwards_sweep(const JntArray &q, const JntArray &qdot, const JntArray &/*qdotdot*/, const Wrenches& f_ext)
7878
{
7979
//if (q.rows() != nj || qdot.rows() != nj || qdotdot.rows() != nj || f_ext.size() != ns)
8080
// return -1;

orocos_kdl/src/jntarray.cpp

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -55,15 +55,13 @@ namespace KDL
5555
data.conservativeResizeLike(Eigen::VectorXd::Zero(newSize));
5656
}
5757

58-
double JntArray::operator()(unsigned int i,unsigned int j)const
58+
double JntArray::operator()(unsigned int i,unsigned int /*j*/)const
5959
{
60-
assert(j==0);
6160
return data(i);
6261
}
6362

64-
double& JntArray::operator()(unsigned int i,unsigned int j)
63+
double& JntArray::operator()(unsigned int i,unsigned int /*j*/)
6564
{
66-
assert(j==0);
6765
return data(i);
6866
}
6967

orocos_kdl/src/kinfam_io.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ std::ostream& operator <<(std::ostream& os, const Joint& joint) {
2929
<<", axis: "<<joint.JointAxis() << ", origin"<<joint.JointOrigin()<<"]";
3030
}
3131

32-
std::istream& operator >>(std::istream& is, Joint& joint) {
32+
std::istream& operator >>(std::istream& is, Joint& /*joint*/) {
3333
return is;
3434
}
3535

@@ -38,7 +38,7 @@ std::ostream& operator <<(std::ostream& os, const Segment& segment) {
3838
return os;
3939
}
4040

41-
std::istream& operator >>(std::istream& is, Segment& segment) {
41+
std::istream& operator >>(std::istream& is, Segment& /*segment*/) {
4242
return is;
4343
}
4444

@@ -50,7 +50,7 @@ std::ostream& operator <<(std::ostream& os, const Chain& chain) {
5050
return os;
5151
}
5252

53-
std::istream& operator >>(std::istream& is, Chain& chain) {
53+
std::istream& operator >>(std::istream& is, Chain& /*chain*/) {
5454
return is;
5555
}
5656

@@ -68,7 +68,7 @@ std::ostream& operator <<(std::ostream& os, SegmentMap::const_iterator root) {
6868
return os << "\n";
6969
}
7070

71-
std::istream& operator >>(std::istream& is, Tree& tree) {
71+
std::istream& operator >>(std::istream& is, Tree& /*tree*/) {
7272
return is;
7373
}
7474

@@ -80,7 +80,7 @@ std::ostream& operator <<(std::ostream& os, const JntArray& array) {
8080
return os;
8181
}
8282

83-
std::istream& operator >>(std::istream& is, JntArray& array) {
83+
std::istream& operator >>(std::istream& is, JntArray& /*array*/) {
8484
return is;
8585
}
8686

@@ -95,7 +95,7 @@ std::ostream& operator <<(std::ostream& os, const Jacobian& jac) {
9595
return os;
9696
}
9797

98-
std::istream& operator >>(std::istream& is, Jacobian& jac) {
98+
std::istream& operator >>(std::istream& is, Jacobian& /*jac*/) {
9999
return is;
100100
}
101101
std::ostream& operator <<(std::ostream& os, const JntSpaceInertiaMatrix& jntspaceinertiamatrix) {
@@ -109,7 +109,7 @@ std::ostream& operator <<(std::ostream& os, const JntSpaceInertiaMatrix& jntspac
109109
return os;
110110
}
111111

112-
std::istream& operator >>(std::istream& is, JntSpaceInertiaMatrix& jntspaceinertiamatrix) {
112+
std::istream& operator >>(std::istream& is, JntSpaceInertiaMatrix& /*jntspaceinertiamatrix*/) {
113113
return is;
114114
}
115115

orocos_kdl/src/path_composite.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,7 @@ void Path_Composite::Add(Path* geom, bool aggregate ) {
8585
gv.insert( gv.end(),std::make_pair(geom,aggregate) );
8686
}
8787

88-
double Path_Composite::LengthToS(double length) {
88+
double Path_Composite::LengthToS(double /*length*/) {
8989
throw Error_MotionPlanning_Not_Applicable();
9090
return 0;
9191
}

orocos_kdl/src/path_cyclic_closed.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ namespace KDL {
4848
Path_Cyclic_Closed::Path_Cyclic_Closed(Path* _geom,int _times, bool _aggregate):
4949
times(_times),geom(_geom), aggregate(_aggregate) {}
5050

51-
double Path_Cyclic_Closed::LengthToS(double length) {
51+
double Path_Cyclic_Closed::LengthToS(double /*length*/) {
5252
throw Error_MotionPlanning_Not_Applicable();
5353
return 0;
5454
}

orocos_kdl/src/path_point.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -55,15 +55,15 @@ double Path_Point::LengthToS(double length) {
5555
double Path_Point::PathLength(){
5656
return 0;
5757
}
58-
Frame Path_Point::Pos(double s) const {
58+
Frame Path_Point::Pos(double /*s*/) const {
5959
return F_base_start;
6060
}
6161

62-
Twist Path_Point::Vel(double s,double sd) const {
62+
Twist Path_Point::Vel(double /*s*/,double /*sd*/) const {
6363
return Twist::Zero();
6464
}
6565

66-
Twist Path_Point::Acc(double s,double sd,double sdd) const {
66+
Twist Path_Point::Acc(double /*s*/,double /*sd*/,double /*sdd*/) const {
6767
return Twist::Zero();
6868
}
6969

orocos_kdl/src/rigidbodyinertia.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ namespace KDL{
2727

2828
const static bool mhi=true;
2929

30-
RigidBodyInertia::RigidBodyInertia(double m_,const Vector& h_,const RotationalInertia& I_,bool mhi):
30+
RigidBodyInertia::RigidBodyInertia(double m_,const Vector& h_,const RotationalInertia& I_,bool /*mhi*/):
3131
m(m_),h(h_),I(I_)
3232
{
3333
}

orocos_kdl/src/rotational_interpolation_sa.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -60,11 +60,11 @@ Rotation RotationalInterpolation_SingleAxis::Pos(double theta) const {
6060
return R_base_start* Rotation::Rot2(rot_start_end,theta);
6161
}
6262

63-
Vector RotationalInterpolation_SingleAxis::Vel(double theta,double thetad) const {
63+
Vector RotationalInterpolation_SingleAxis::Vel(double /*theta*/,double thetad) const {
6464
return R_base_start * ( rot_start_end*thetad );
6565
}
6666

67-
Vector RotationalInterpolation_SingleAxis::Acc(double theta,double thetad,double thetadd) const {
67+
Vector RotationalInterpolation_SingleAxis::Acc(double /*theta*/,double /*thetad*/,double thetadd) const {
6868
return R_base_start * ( rot_start_end* thetadd);
6969
}
7070

@@ -85,4 +85,3 @@ RotationalInterpolation* RotationalInterpolation_SingleAxis::Clone() const {
8585
}
8686

8787
}
88-

orocos_kdl/src/trajectory_stationary.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -35,13 +35,13 @@ namespace KDL {
3535
virtual double Duration() const {
3636
return duration;
3737
}
38-
virtual Frame Pos(double time) const {
38+
virtual Frame Pos(double /*time*/) const {
3939
return pos;
4040
}
41-
virtual Twist Vel(double time) const {
41+
virtual Twist Vel(double /*time*/) const {
4242
return Twist::Zero();
4343
}
44-
virtual Twist Acc(double time) const {
44+
virtual Twist Acc(double /*time*/) const {
4545
return Twist::Zero();
4646
}
4747
virtual void Write(std::ostream& os) const;

orocos_kdl/src/utilities/error.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ class Error_IO : public Error {
7070
std::string msg;
7171
int typenr;
7272
public:
73-
Error_IO(const std::string& _msg="Unspecified I/O Error",int typenr=0):msg(_msg) {}
73+
Error_IO(const std::string& _msg="Unspecified I/O Error",int /*typenr*/=0):msg(_msg) {}
7474
virtual const char* Description() const {return msg.c_str();}
7575
virtual int GetType() const {return typenr;}
7676
};

orocos_kdl/src/velocityprofile_dirac.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ namespace KDL {
7575
return 0;
7676
}
7777

78-
double VelocityProfile_Dirac::Acc(double time) const {
78+
double VelocityProfile_Dirac::Acc(double /*time*/) const {
7979
throw Error_MotionPlanning_Incompatible();
8080
return 0;
8181
}

orocos_kdl/src/velocityprofile_rect.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,7 @@ double VelocityProfile_Rectangular::Vel(double time) const {
118118
}
119119
}
120120

121-
double VelocityProfile_Rectangular::Acc(double time) const {
121+
double VelocityProfile_Rectangular::Acc(double /*time*/) const {
122122
throw Error_MotionPlanning_Incompatible();
123123
return 0;
124124
}

orocos_kdl/src/velocityprofile_spline.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ VelocityProfile_Spline::~VelocityProfile_Spline()
4848
return;
4949
}
5050

51-
void VelocityProfile_Spline::SetProfile(double pos1, double pos2)
51+
void VelocityProfile_Spline::SetProfile(double /*pos1*/, double /*pos2*/)
5252
{
5353
return;
5454
}

orocos_kdl/src/velocityprofile_trap.cpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -190,9 +190,4 @@ void VelocityProfile_Trap::Write(std::ostream& os) const {
190190
os << "TRAPEZOIDAL[" << maxvel << "," << maxacc <<"]";
191191
}
192192

193-
194-
195-
196-
197193
}
198-

0 commit comments

Comments
 (0)