diff --git a/src/Mod/Robot/App/PropertyTrajectory.cpp b/src/Mod/Robot/App/PropertyTrajectory.cpp index 5ec8536df2..9282cb9c79 100644 --- a/src/Mod/Robot/App/PropertyTrajectory.cpp +++ b/src/Mod/Robot/App/PropertyTrajectory.cpp @@ -28,7 +28,6 @@ #endif -#include #include #include #include diff --git a/src/Mod/Robot/App/Robot6AxisPyImp.cpp b/src/Mod/Robot/App/Robot6AxisPyImp.cpp index cb1b40ea02..aaf4f54993 100644 --- a/src/Mod/Robot/App/Robot6AxisPyImp.cpp +++ b/src/Mod/Robot/App/Robot6AxisPyImp.cpp @@ -169,7 +169,7 @@ Py::Object Robot6AxisPy::getBase(void) const return Py::Object(); } -void Robot6AxisPy::setBase(Py::Object arg) +void Robot6AxisPy::setBase(Py::Object /*arg*/) { } diff --git a/src/Mod/Robot/App/Simulation.cpp b/src/Mod/Robot/App/Simulation.cpp index b3c175b050..0a74fef99e 100644 --- a/src/Mod/Robot/App/Simulation.cpp +++ b/src/Mod/Robot/App/Simulation.cpp @@ -77,10 +77,9 @@ void Simulation::step(double tick) Pos += tick; } -void Simulation::setToWaypoint(unsigned int n) +void Simulation::setToWaypoint(unsigned int) { - } void Simulation::setToTime(float t) diff --git a/src/Mod/Robot/App/kdl_cp/chainidsolver_vereshchagin.cpp b/src/Mod/Robot/App/kdl_cp/chainidsolver_vereshchagin.cpp index 034d174100..3919497124 100644 --- a/src/Mod/Robot/App/kdl_cp/chainidsolver_vereshchagin.cpp +++ b/src/Mod/Robot/App/kdl_cp/chainidsolver_vereshchagin.cpp @@ -61,7 +61,7 @@ int ChainIdSolver_Vereshchagin::CartToJnt(const JntArray &q, const JntArray &q_d return 0; } -void ChainIdSolver_Vereshchagin::initial_upwards_sweep(const JntArray &q, const JntArray &qdot, const JntArray &qdotdot, const Wrenches& f_ext) +void ChainIdSolver_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; diff --git a/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv.hpp b/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv.hpp index 9e8abbd024..0b69d1dec5 100644 --- a/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv.hpp +++ b/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv.hpp @@ -78,7 +78,7 @@ namespace KDL * not (yet) implemented. * */ - virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out){return -1;}; + virtual int CartToJnt(const JntArray& /*q_init*/, const FrameVel& /*v_in*/, JntArrayVel& /*q_out*/){return -1;}; /** * Retrieve the number of singular values of the jacobian that are < eps; diff --git a/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv_givens.hpp b/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv_givens.hpp index 0371d362f3..76f94da2a1 100644 --- a/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv_givens.hpp +++ b/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv_givens.hpp @@ -39,7 +39,7 @@ namespace KDL * not (yet) implemented. * */ - virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out){return -1;}; + virtual int CartToJnt(const JntArray& /*q_init*/, const FrameVel& /*v_in*/, JntArrayVel& /*q_out*/){return -1;}; private: const Chain chain; ChainJntToJacSolver jnt2jac; diff --git a/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv_nso.hpp b/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv_nso.hpp index b9f2175137..bdc81099c4 100644 --- a/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv_nso.hpp +++ b/src/Mod/Robot/App/kdl_cp/chainiksolvervel_pinv_nso.hpp @@ -75,7 +75,7 @@ namespace KDL * not (yet) implemented. * */ - virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out){return -1;}; + virtual int CartToJnt(const JntArray& /*q_init*/, const FrameVel& /*v_in*/, JntArrayVel& /*q_out*/){return -1;}; /** *Set joint weights for optimization criterion diff --git a/src/Mod/Robot/App/kdl_cp/chainiksolvervel_wdls.hpp b/src/Mod/Robot/App/kdl_cp/chainiksolvervel_wdls.hpp index e1068c3806..2b74c7c196 100644 --- a/src/Mod/Robot/App/kdl_cp/chainiksolvervel_wdls.hpp +++ b/src/Mod/Robot/App/kdl_cp/chainiksolvervel_wdls.hpp @@ -103,7 +103,7 @@ namespace KDL * not (yet) implemented. * */ - virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out){return -1;}; + virtual int CartToJnt(const JntArray& /*q_init*/, const FrameVel& /*v_in*/, JntArrayVel& /*q_out*/){return -1;}; /** * Set the joint space weighting matrix diff --git a/src/Mod/Robot/App/kdl_cp/kinfam_io.cpp b/src/Mod/Robot/App/kdl_cp/kinfam_io.cpp index 5904845729..c42dec876b 100644 --- a/src/Mod/Robot/App/kdl_cp/kinfam_io.cpp +++ b/src/Mod/Robot/App/kdl_cp/kinfam_io.cpp @@ -28,7 +28,7 @@ std::ostream& operator <<(std::ostream& os, const Joint& joint) { <<", axis: "<>(std::istream& is, Joint& joint) { +std::istream& operator >>(std::istream& is, Joint& /*joint*/) { return is; } @@ -37,7 +37,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; } @@ -49,7 +49,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; } @@ -67,7 +67,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; } @@ -79,7 +79,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; } @@ -94,7 +94,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) { @@ -108,7 +108,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; } } diff --git a/src/Mod/Robot/App/kdl_cp/path_composite.cpp b/src/Mod/Robot/App/kdl_cp/path_composite.cpp index 5435d88484..ab344a6b13 100644 --- a/src/Mod/Robot/App/kdl_cp/path_composite.cpp +++ b/src/Mod/Robot/App/kdl_cp/path_composite.cpp @@ -84,9 +84,8 @@ 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; } double Path_Composite::PathLength() { diff --git a/src/Mod/Robot/App/kdl_cp/path_cyclic_closed.cpp b/src/Mod/Robot/App/kdl_cp/path_cyclic_closed.cpp index fa5c65f307..a8bbe5d264 100644 --- a/src/Mod/Robot/App/kdl_cp/path_cyclic_closed.cpp +++ b/src/Mod/Robot/App/kdl_cp/path_cyclic_closed.cpp @@ -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; } diff --git a/src/Mod/Robot/App/kdl_cp/path_point.cpp b/src/Mod/Robot/App/kdl_cp/path_point.cpp index 854843dc60..1ccae4345a 100644 --- a/src/Mod/Robot/App/kdl_cp/path_point.cpp +++ b/src/Mod/Robot/App/kdl_cp/path_point.cpp @@ -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(); } diff --git a/src/Mod/Robot/App/kdl_cp/rigidbodyinertia.cpp b/src/Mod/Robot/App/kdl_cp/rigidbodyinertia.cpp index 2313fce56e..37ca6399d4 100644 --- a/src/Mod/Robot/App/kdl_cp/rigidbodyinertia.cpp +++ b/src/Mod/Robot/App/kdl_cp/rigidbodyinertia.cpp @@ -29,7 +29,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_) { } diff --git a/src/Mod/Robot/App/kdl_cp/rotational_interpolation_sa.cpp b/src/Mod/Robot/App/kdl_cp/rotational_interpolation_sa.cpp index 6a0accd144..e20d36f0fc 100644 --- a/src/Mod/Robot/App/kdl_cp/rotational_interpolation_sa.cpp +++ b/src/Mod/Robot/App/kdl_cp/rotational_interpolation_sa.cpp @@ -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); } diff --git a/src/Mod/Robot/App/kdl_cp/trajectory_stationary.hpp b/src/Mod/Robot/App/kdl_cp/trajectory_stationary.hpp index 1d5343b8ed..824dbeff47 100644 --- a/src/Mod/Robot/App/kdl_cp/trajectory_stationary.hpp +++ b/src/Mod/Robot/App/kdl_cp/trajectory_stationary.hpp @@ -48,13 +48,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; diff --git a/src/Mod/Robot/App/kdl_cp/utilities/error.h b/src/Mod/Robot/App/kdl_cp/utilities/error.h index 693c3dc253..6e9bd2e145 100644 --- a/src/Mod/Robot/App/kdl_cp/utilities/error.h +++ b/src/Mod/Robot/App/kdl_cp/utilities/error.h @@ -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;} }; diff --git a/src/Mod/Robot/App/kdl_cp/velocityprofile_dirac.cpp b/src/Mod/Robot/App/kdl_cp/velocityprofile_dirac.cpp index 9f4bc76391..3627852841 100644 --- a/src/Mod/Robot/App/kdl_cp/velocityprofile_dirac.cpp +++ b/src/Mod/Robot/App/kdl_cp/velocityprofile_dirac.cpp @@ -70,9 +70,8 @@ namespace KDL { return 0; } - double VelocityProfile_Dirac::Acc(double time) const { + double VelocityProfile_Dirac::Acc(double /*time*/) const { throw Error_MotionPlanning_Incompatible(); - return 0; } diff --git a/src/Mod/Robot/App/kdl_cp/velocityprofile_rect.cpp b/src/Mod/Robot/App/kdl_cp/velocityprofile_rect.cpp index 7992c1e99a..d255b6f01c 100644 --- a/src/Mod/Robot/App/kdl_cp/velocityprofile_rect.cpp +++ b/src/Mod/Robot/App/kdl_cp/velocityprofile_rect.cpp @@ -118,9 +118,8 @@ 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; } diff --git a/src/Mod/Robot/App/kdl_cp/velocityprofile_spline.cpp b/src/Mod/Robot/App/kdl_cp/velocityprofile_spline.cpp index ec651ed9b1..de37ecbf91 100644 --- a/src/Mod/Robot/App/kdl_cp/velocityprofile_spline.cpp +++ b/src/Mod/Robot/App/kdl_cp/velocityprofile_spline.cpp @@ -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; } diff --git a/src/Mod/Robot/Gui/Command.cpp b/src/Mod/Robot/Gui/Command.cpp index 785fadff73..194d0f650d 100644 --- a/src/Mod/Robot/Gui/Command.cpp +++ b/src/Mod/Robot/Gui/Command.cpp @@ -61,7 +61,7 @@ CmdRobotSetHomePos::CmdRobotSetHomePos() } -void CmdRobotSetHomePos::activated(int iMsg) +void CmdRobotSetHomePos::activated(int) { const char * SelFilter = "SELECT Robot::RobotObject COUNT 1 "; @@ -110,7 +110,7 @@ CmdRobotRestoreHomePos::CmdRobotRestoreHomePos() } -void CmdRobotRestoreHomePos::activated(int iMsg) +void CmdRobotRestoreHomePos::activated(int) { const char * SelFilter = "SELECT Robot::RobotObject COUNT 1 "; @@ -164,7 +164,7 @@ CmdRobotConstraintAxle::CmdRobotConstraintAxle() } -void CmdRobotConstraintAxle::activated(int iMsg) +void CmdRobotConstraintAxle::activated(int) { std::string FeatName = getUniqueObjectName("Robot"); std::string RobotPath = "Mod/Robot/Lib/Kuka/kr500_1.wrl"; @@ -205,7 +205,7 @@ CmdRobotSimulate::CmdRobotSimulate() } -void CmdRobotSimulate::activated(int iMsg) +void CmdRobotSimulate::activated(int) { #if 1 const char * SelFilter = diff --git a/src/Mod/Robot/Gui/CommandExport.cpp b/src/Mod/Robot/Gui/CommandExport.cpp index 8eeb0fe120..1a131b0b2b 100644 --- a/src/Mod/Robot/Gui/CommandExport.cpp +++ b/src/Mod/Robot/Gui/CommandExport.cpp @@ -56,7 +56,7 @@ CmdRobotExportKukaCompact::CmdRobotExportKukaCompact() } -void CmdRobotExportKukaCompact::activated(int iMsg) +void CmdRobotExportKukaCompact::activated(int) { unsigned int n1 = getSelection().countObjectsOfType(Robot::RobotObject::getClassTypeId()); unsigned int n2 = getSelection().countObjectsOfType(Robot::TrajectoryObject::getClassTypeId()); @@ -118,7 +118,7 @@ CmdRobotExportKukaFull::CmdRobotExportKukaFull() } -void CmdRobotExportKukaFull::activated(int iMsg) +void CmdRobotExportKukaFull::activated(int) { unsigned int n1 = getSelection().countObjectsOfType(Robot::RobotObject::getClassTypeId()); unsigned int n2 = getSelection().countObjectsOfType(Robot::TrajectoryObject::getClassTypeId()); diff --git a/src/Mod/Robot/Gui/CommandInsertRobot.cpp b/src/Mod/Robot/Gui/CommandInsertRobot.cpp index 6067a2d8a2..b5eb6ed632 100644 --- a/src/Mod/Robot/Gui/CommandInsertRobot.cpp +++ b/src/Mod/Robot/Gui/CommandInsertRobot.cpp @@ -57,7 +57,7 @@ CmdRobotInsertKukaIR500::CmdRobotInsertKukaIR500() } -void CmdRobotInsertKukaIR500::activated(int iMsg) +void CmdRobotInsertKukaIR500::activated(int) { std::string FeatName = getUniqueObjectName("Robot"); std::string RobotPath = "Mod/Robot/Lib/Kuka/kr500_1.wrl"; @@ -99,7 +99,7 @@ CmdRobotInsertKukaIR16::CmdRobotInsertKukaIR16() } -void CmdRobotInsertKukaIR16::activated(int iMsg) +void CmdRobotInsertKukaIR16::activated(int) { std::string FeatName = getUniqueObjectName("Robot"); std::string RobotPath = "Mod/Robot/Lib/Kuka/kr16.wrl"; @@ -140,7 +140,7 @@ CmdRobotInsertKukaIR210::CmdRobotInsertKukaIR210() } -void CmdRobotInsertKukaIR210::activated(int iMsg) +void CmdRobotInsertKukaIR210::activated(int) { std::string FeatName = getUniqueObjectName("Robot"); std::string RobotPath = "Mod/Robot/Lib/Kuka/kr210.WRL"; @@ -180,7 +180,7 @@ CmdRobotInsertKukaIR125::CmdRobotInsertKukaIR125() } -void CmdRobotInsertKukaIR125::activated(int iMsg) +void CmdRobotInsertKukaIR125::activated(int) { std::string FeatName = getUniqueObjectName("Robot"); std::string RobotPath = "Mod/Robot/Lib/Kuka/kr125_3.wrl"; @@ -221,7 +221,7 @@ CmdRobotAddToolShape::CmdRobotAddToolShape() } -void CmdRobotAddToolShape::activated(int iMsg) +void CmdRobotAddToolShape::activated(int) { std::vector robots = getSelection() .getObjectsOfType(Robot::RobotObject::getClassTypeId()); diff --git a/src/Mod/Robot/Gui/CommandTrajectory.cpp b/src/Mod/Robot/Gui/CommandTrajectory.cpp index da1eeaaa21..6aaeffba67 100644 --- a/src/Mod/Robot/Gui/CommandTrajectory.cpp +++ b/src/Mod/Robot/Gui/CommandTrajectory.cpp @@ -68,7 +68,7 @@ CmdRobotCreateTrajectory::CmdRobotCreateTrajectory() } -void CmdRobotCreateTrajectory::activated(int iMsg) +void CmdRobotCreateTrajectory::activated(int) { std::string FeatName = getUniqueObjectName("Trajectory"); @@ -102,7 +102,7 @@ CmdRobotInsertWaypoint::CmdRobotInsertWaypoint() } -void CmdRobotInsertWaypoint::activated(int iMsg) +void CmdRobotInsertWaypoint::activated(int) { unsigned int n1 = getSelection().countObjectsOfType(Robot::RobotObject::getClassTypeId()); unsigned int n2 = getSelection().countObjectsOfType(Robot::TrajectoryObject::getClassTypeId()); @@ -160,7 +160,7 @@ CmdRobotInsertWaypointPreselect::CmdRobotInsertWaypointPreselect() } -void CmdRobotInsertWaypointPreselect::activated(int iMsg) +void CmdRobotInsertWaypointPreselect::activated(int) { if (getSelection().size() != 1 ) { @@ -223,7 +223,7 @@ CmdRobotSetDefaultOrientation::CmdRobotSetDefaultOrientation() } -void CmdRobotSetDefaultOrientation::activated(int iMsg) +void CmdRobotSetDefaultOrientation::activated(int) { // create placement dialog Gui::Dialog::Placement *Dlg = new Gui::Dialog::Placement(); @@ -262,7 +262,7 @@ CmdRobotSetDefaultValues::CmdRobotSetDefaultValues() } -void CmdRobotSetDefaultValues::activated(int iMsg) +void CmdRobotSetDefaultValues::activated(int) { bool ok; @@ -328,7 +328,7 @@ CmdRobotEdge2Trac::CmdRobotEdge2Trac() } -void CmdRobotEdge2Trac::activated(int iMsg) +void CmdRobotEdge2Trac::activated(int) { /* App::DocumentObject *obj = this->getDocument()->getObject(FeatName.c_str()); @@ -392,7 +392,7 @@ CmdRobotTrajectoryDressUp::CmdRobotTrajectoryDressUp() } -void CmdRobotTrajectoryDressUp::activated(int iMsg) +void CmdRobotTrajectoryDressUp::activated(int) { Gui::SelectionFilter ObjectFilterDressUp("SELECT Robot::TrajectoryDressUpObject COUNT 1"); Gui::SelectionFilter ObjectFilter("SELECT Robot::TrajectoryObject COUNT 1"); @@ -439,7 +439,7 @@ CmdRobotTrajectoryCompound::CmdRobotTrajectoryCompound() } -void CmdRobotTrajectoryCompound::activated(int iMsg) +void CmdRobotTrajectoryCompound::activated(int) { Gui::SelectionFilter ObjectFilter("SELECT Robot::TrajectoryCompound COUNT 1"); diff --git a/src/Mod/Robot/Gui/ViewProviderEdge2TracObject.cpp b/src/Mod/Robot/Gui/ViewProviderEdge2TracObject.cpp index b529c36c70..bba0f5ce1e 100644 --- a/src/Mod/Robot/Gui/ViewProviderEdge2TracObject.cpp +++ b/src/Mod/Robot/Gui/ViewProviderEdge2TracObject.cpp @@ -43,15 +43,14 @@ bool ViewProviderEdge2TracObject::doubleClicked(void) } -bool ViewProviderEdge2TracObject::setEdit(int ModNum) +bool ViewProviderEdge2TracObject::setEdit(int) { Gui::TaskView::TaskDialog* dlg = new TaskDlgEdge2Trac(static_cast(getObject())); Gui::Control().showDialog(dlg); return true; } -void ViewProviderEdge2TracObject::unsetEdit(int ModNum) +void ViewProviderEdge2TracObject::unsetEdit(int) { - } diff --git a/src/Mod/Robot/Gui/ViewProviderTrajectoryCompound.cpp b/src/Mod/Robot/Gui/ViewProviderTrajectoryCompound.cpp index c45e22575a..ba16ea5d82 100644 --- a/src/Mod/Robot/Gui/ViewProviderTrajectoryCompound.cpp +++ b/src/Mod/Robot/Gui/ViewProviderTrajectoryCompound.cpp @@ -44,7 +44,7 @@ PROPERTY_SOURCE(RobotGui::ViewProviderTrajectoryCompound, RobotGui::ViewProvider //} -bool ViewProviderTrajectoryCompound::setEdit(int ModNum) +bool ViewProviderTrajectoryCompound::setEdit(int) { Gui::TaskView::TaskDialog* dlg = new TaskDlgTrajectoryCompound(dynamic_cast(getObject())); Gui::Control().showDialog(dlg); @@ -52,7 +52,7 @@ bool ViewProviderTrajectoryCompound::setEdit(int ModNum) } -void ViewProviderTrajectoryCompound::unsetEdit(int ModNum) +void ViewProviderTrajectoryCompound::unsetEdit(int) { // when pressing ESC make sure to close the dialog Gui::Control().closeDialog(); diff --git a/src/Mod/Robot/Gui/ViewProviderTrajectoryDressUp.cpp b/src/Mod/Robot/Gui/ViewProviderTrajectoryDressUp.cpp index f539f3c8d3..639c5e41d7 100644 --- a/src/Mod/Robot/Gui/ViewProviderTrajectoryDressUp.cpp +++ b/src/Mod/Robot/Gui/ViewProviderTrajectoryDressUp.cpp @@ -43,14 +43,14 @@ PROPERTY_SOURCE(RobotGui::ViewProviderTrajectoryDressUp, RobotGui::ViewProviderT //} // -bool ViewProviderTrajectoryDressUp::setEdit(int ModNum) +bool ViewProviderTrajectoryDressUp::setEdit(int) { Gui::TaskView::TaskDialog* dlg = new TaskDlgTrajectoryDressUp(static_cast(getObject())); Gui::Control().showDialog(dlg); return true; } -void ViewProviderTrajectoryDressUp::unsetEdit(int ModNum) +void ViewProviderTrajectoryDressUp::unsetEdit(int) { // when pressing ESC make sure to close the dialog Gui::Control().closeDialog();