Skip to content

Commit

Permalink
Fix unused-parameter
Browse files Browse the repository at this point in the history
  • Loading branch information
MatthijsBurgh committed Sep 30, 2022
1 parent c92d084 commit 3c85f21
Show file tree
Hide file tree
Showing 15 changed files with 26 additions and 34 deletions.
2 changes: 1 addition & 1 deletion orocos_kdl/src/chainfdsolver_recursive_newton_euler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ namespace KDL{
return (error = E_NOERROR);
}

void ChainFdSolver_RNE::RK4Integrator(unsigned int& nj, const double& t, double& dt, KDL::JntArray& q, KDL::JntArray& q_dot,
void ChainFdSolver_RNE::RK4Integrator(unsigned int& nj, const double& /*t*/, double& dt, KDL::JntArray& q, KDL::JntArray& q_dot,
KDL::JntArray& torques, KDL::Wrenches& f_ext, KDL::ChainFdSolver_RNE& fdsolver,
KDL::JntArray& q_dotdot, KDL::JntArray& dq, KDL::JntArray& dq_dot,
KDL::JntArray& q_temp, KDL::JntArray& q_dot_temp)
Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/chainhdsolver_vereshchagin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ int ChainHdSolver_Vereshchagin::CartToJnt(const JntArray &q, const JntArray &q_d
return (error = E_NOERROR);
}

void ChainHdSolver_Vereshchagin::initial_upwards_sweep(const JntArray &q, const JntArray &qdot, const JntArray &qdotdot, const Wrenches& f_ext)
void ChainHdSolver_Vereshchagin::initial_upwards_sweep(const JntArray &q, const JntArray &qdot, const JntArray &/*qdotdot*/, const Wrenches& f_ext)
{
//if (q.rows() != nj || qdot.rows() != nj || qdotdot.rows() != nj || f_ext.size() != ns)
// return -1;
Expand Down
6 changes: 2 additions & 4 deletions orocos_kdl/src/jntarray.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,15 +55,13 @@ namespace KDL
data.conservativeResizeLike(Eigen::VectorXd::Zero(newSize));
}

double JntArray::operator()(unsigned int i,unsigned int j)const
double JntArray::operator()(unsigned int i,unsigned int /*j*/)const
{
assert(j==0);
return data(i);
}

double& JntArray::operator()(unsigned int i,unsigned int j)
double& JntArray::operator()(unsigned int i,unsigned int /*j*/)
{
assert(j==0);
return data(i);
}

Expand Down
14 changes: 7 additions & 7 deletions orocos_kdl/src/kinfam_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ std::ostream& operator <<(std::ostream& os, const Joint& joint) {
<<", axis: "<<joint.JointAxis() << ", origin"<<joint.JointOrigin()<<"]";
}

std::istream& operator >>(std::istream& is, Joint& joint) {
std::istream& operator >>(std::istream& is, Joint& /*joint*/) {
return is;
}

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

std::istream& operator >>(std::istream& is, Segment& segment) {
std::istream& operator >>(std::istream& is, Segment& /*segment*/) {
return is;
}

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

std::istream& operator >>(std::istream& is, Chain& chain) {
std::istream& operator >>(std::istream& is, Chain& /*chain*/) {
return is;
}

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

std::istream& operator >>(std::istream& is, Tree& tree) {
std::istream& operator >>(std::istream& is, Tree& /*tree*/) {
return is;
}

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

std::istream& operator >>(std::istream& is, JntArray& array) {
std::istream& operator >>(std::istream& is, JntArray& /*array*/) {
return is;
}

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

std::istream& operator >>(std::istream& is, Jacobian& jac) {
std::istream& operator >>(std::istream& is, Jacobian& /*jac*/) {
return is;
}
std::ostream& operator <<(std::ostream& os, const JntSpaceInertiaMatrix& jntspaceinertiamatrix) {
Expand All @@ -109,7 +109,7 @@ std::ostream& operator <<(std::ostream& os, const JntSpaceInertiaMatrix& jntspac
return os;
}

std::istream& operator >>(std::istream& is, JntSpaceInertiaMatrix& jntspaceinertiamatrix) {
std::istream& operator >>(std::istream& is, JntSpaceInertiaMatrix& /*jntspaceinertiamatrix*/) {
return is;
}

Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/path_composite.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ void Path_Composite::Add(Path* geom, bool aggregate ) {
gv.insert( gv.end(),std::make_pair(geom,aggregate) );
}

double Path_Composite::LengthToS(double length) {
double Path_Composite::LengthToS(double /*length*/) {
throw Error_MotionPlanning_Not_Applicable();
return 0;
}
Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/path_cyclic_closed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ namespace KDL {
Path_Cyclic_Closed::Path_Cyclic_Closed(Path* _geom,int _times, bool _aggregate):
times(_times),geom(_geom), aggregate(_aggregate) {}

double Path_Cyclic_Closed::LengthToS(double length) {
double Path_Cyclic_Closed::LengthToS(double /*length*/) {
throw Error_MotionPlanning_Not_Applicable();
return 0;
}
Expand Down
6 changes: 3 additions & 3 deletions orocos_kdl/src/path_point.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,15 +55,15 @@ double Path_Point::LengthToS(double length) {
double Path_Point::PathLength(){
return 0;
}
Frame Path_Point::Pos(double s) const {
Frame Path_Point::Pos(double /*s*/) const {
return F_base_start;
}

Twist Path_Point::Vel(double s,double sd) const {
Twist Path_Point::Vel(double /*s*/,double /*sd*/) const {
return Twist::Zero();
}

Twist Path_Point::Acc(double s,double sd,double sdd) const {
Twist Path_Point::Acc(double /*s*/,double /*sd*/,double /*sdd*/) const {
return Twist::Zero();
}

Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/rigidbodyinertia.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace KDL{

const static bool mhi=true;

RigidBodyInertia::RigidBodyInertia(double m_,const Vector& h_,const RotationalInertia& I_,bool mhi):
RigidBodyInertia::RigidBodyInertia(double m_,const Vector& h_,const RotationalInertia& I_,bool /*mhi*/):
m(m_),h(h_),I(I_)
{
}
Expand Down
5 changes: 2 additions & 3 deletions orocos_kdl/src/rotational_interpolation_sa.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,11 +60,11 @@ Rotation RotationalInterpolation_SingleAxis::Pos(double theta) const {
return R_base_start* Rotation::Rot2(rot_start_end,theta);
}

Vector RotationalInterpolation_SingleAxis::Vel(double theta,double thetad) const {
Vector RotationalInterpolation_SingleAxis::Vel(double /*theta*/,double thetad) const {
return R_base_start * ( rot_start_end*thetad );
}

Vector RotationalInterpolation_SingleAxis::Acc(double theta,double thetad,double thetadd) const {
Vector RotationalInterpolation_SingleAxis::Acc(double /*theta*/,double /*thetad*/,double thetadd) const {
return R_base_start * ( rot_start_end* thetadd);
}

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

}

6 changes: 3 additions & 3 deletions orocos_kdl/src/trajectory_stationary.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,13 +35,13 @@ namespace KDL {
virtual double Duration() const {
return duration;
}
virtual Frame Pos(double time) const {
virtual Frame Pos(double /*time*/) const {
return pos;
}
virtual Twist Vel(double time) const {
virtual Twist Vel(double /*time*/) const {
return Twist::Zero();
}
virtual Twist Acc(double time) const {
virtual Twist Acc(double /*time*/) const {
return Twist::Zero();
}
virtual void Write(std::ostream& os) const;
Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/utilities/error.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class Error_IO : public Error {
std::string msg;
int typenr;
public:
Error_IO(const std::string& _msg="Unspecified I/O Error",int typenr=0):msg(_msg) {}
Error_IO(const std::string& _msg="Unspecified I/O Error",int /*typenr*/=0):msg(_msg) {}
virtual const char* Description() const {return msg.c_str();}
virtual int GetType() const {return typenr;}
};
Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/velocityprofile_dirac.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ namespace KDL {
return 0;
}

double VelocityProfile_Dirac::Acc(double time) const {
double VelocityProfile_Dirac::Acc(double /*time*/) const {
throw Error_MotionPlanning_Incompatible();
return 0;
}
Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/velocityprofile_rect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ double VelocityProfile_Rectangular::Vel(double time) const {
}
}

double VelocityProfile_Rectangular::Acc(double time) const {
double VelocityProfile_Rectangular::Acc(double /*time*/) const {
throw Error_MotionPlanning_Incompatible();
return 0;
}
Expand Down
2 changes: 1 addition & 1 deletion orocos_kdl/src/velocityprofile_spline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ VelocityProfile_Spline::~VelocityProfile_Spline()
return;
}

void VelocityProfile_Spline::SetProfile(double pos1, double pos2)
void VelocityProfile_Spline::SetProfile(double /*pos1*/, double /*pos2*/)
{
return;
}
Expand Down
5 changes: 0 additions & 5 deletions orocos_kdl/src/velocityprofile_trap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,9 +190,4 @@ void VelocityProfile_Trap::Write(std::ostream& os) const {
os << "TRAPEZOIDAL[" << maxvel << "," << maxacc <<"]";
}





}

0 comments on commit 3c85f21

Please sign in to comment.