From d80c05e18631cd51430d19141f38524f9351b210 Mon Sep 17 00:00:00 2001 From: wmayer Date: Sat, 20 Aug 2016 17:21:01 +0200 Subject: [PATCH] fix Coverity issues --- src/Mod/Raytracing/App/LuxProject.cpp | 2 +- src/Mod/Raytracing/App/RayProject.cpp | 2 +- src/Mod/Raytracing/Gui/Command.cpp | 18 +-- .../ReverseEngineering/App/ApproxSurface.cpp | 3 + src/Mod/Robot/App/Trajectory.cpp | 113 +++++++++--------- src/Mod/Robot/App/TrajectoryPy.xml | 3 - src/Mod/Robot/App/TrajectoryPyImp.cpp | 7 +- src/Mod/Robot/App/Waypoint.cpp | 32 +++-- src/Mod/Robot/App/Waypoint.h | 8 +- src/Mod/Robot/Gui/CommandExport.cpp | 22 ++-- src/Mod/Robot/Gui/CommandTrajectory.cpp | 10 +- src/Mod/Robot/Gui/TrajectorySimulate.cpp | 2 +- .../Robot/Gui/ViewProviderEdge2TracObject.cpp | 4 +- src/Mod/Robot/Gui/ViewProviderRobotObject.h | 30 ++--- .../Gui/ViewProviderTrajectoryDressUp.cpp | 2 +- .../Sketcher/Gui/TaskSketcherValidation.cpp | 8 +- src/Mod/Sketcher/Gui/ViewProviderSketch.h | 1 - src/Mod/Web/App/AppWeb.cpp | 2 - 18 files changed, 133 insertions(+), 136 deletions(-) diff --git a/src/Mod/Raytracing/App/LuxProject.cpp b/src/Mod/Raytracing/App/LuxProject.cpp index dad3e00b7..bcc227546 100644 --- a/src/Mod/Raytracing/App/LuxProject.cpp +++ b/src/Mod/Raytracing/App/LuxProject.cpp @@ -105,7 +105,7 @@ App::DocumentObjectExecReturn *LuxProject::execute(void) const std::vector &Grp = Group.getValues(); for (std::vector::const_iterator It= Grp.begin();It!=Grp.end();++It) { if ((*It)->getTypeId().isDerivedFrom(Raytracing::RaySegment::getClassTypeId())) { - Raytracing::RaySegment *View = dynamic_cast(*It); + Raytracing::RaySegment *View = static_cast(*It); ofile << View->Result.getValue(); ofile << endl; } diff --git a/src/Mod/Raytracing/App/RayProject.cpp b/src/Mod/Raytracing/App/RayProject.cpp index 6a7e8b994..bdcebf367 100644 --- a/src/Mod/Raytracing/App/RayProject.cpp +++ b/src/Mod/Raytracing/App/RayProject.cpp @@ -99,7 +99,7 @@ App::DocumentObjectExecReturn *RayProject::execute(void) const std::vector &Grp = Group.getValues(); for (std::vector::const_iterator It= Grp.begin();It!=Grp.end();++It) { if ((*It)->getTypeId().isDerivedFrom(Raytracing::RaySegment::getClassTypeId())) { - Raytracing::RaySegment *View = dynamic_cast(*It); + Raytracing::RaySegment *View = static_cast(*It); ofile << View->Result.getValue(); ofile << endl << endl << endl; } diff --git a/src/Mod/Raytracing/Gui/Command.cpp b/src/Mod/Raytracing/Gui/Command.cpp index 4868d3883..15101a5ac 100644 --- a/src/Mod/Raytracing/Gui/Command.cpp +++ b/src/Mod/Raytracing/Gui/Command.cpp @@ -369,9 +369,6 @@ Gui::Action * CmdRaytracingNewPovrayProject::createAction(void) pcAction->setDropDownMenu(true); applyCommandData(this->className(), pcAction); - QAction* defaultAction = 0; - int defaultId = 0; - std::string path = App::Application::getResourceDir(); path += "Mod/Raytracing/Templates/"; QDir dir(QString::fromUtf8(path.c_str()), QString::fromLatin1("*.pov")); @@ -385,11 +382,7 @@ Gui::Action * CmdRaytracingNewPovrayProject::createAction(void) _pcAction = pcAction; languageChange(); - if (defaultAction) { - pcAction->setIcon(defaultAction->icon()); - pcAction->setProperty("defaultAction", QVariant(defaultId)); - } - else if (!pcAction->actions().isEmpty()) { + if (!pcAction->actions().isEmpty()) { pcAction->setIcon(pcAction->actions()[0]->icon()); pcAction->setProperty("defaultAction", QVariant(0)); } @@ -767,9 +760,6 @@ Gui::Action * CmdRaytracingNewLuxProject::createAction(void) pcAction->setDropDownMenu(true); applyCommandData(this->className(), pcAction); - QAction* defaultAction = 0; - int defaultId = 0; - std::string path = App::Application::getResourceDir(); path += "Mod/Raytracing/Templates/"; QDir dir(QString::fromUtf8(path.c_str()), QString::fromLatin1("*.lxs")); @@ -783,11 +773,7 @@ Gui::Action * CmdRaytracingNewLuxProject::createAction(void) _pcAction = pcAction; languageChange(); - if (defaultAction) { - pcAction->setIcon(defaultAction->icon()); - pcAction->setProperty("defaultAction", QVariant(defaultId)); - } - else if (!pcAction->actions().isEmpty()) { + if (!pcAction->actions().isEmpty()) { pcAction->setIcon(pcAction->actions()[0]->icon()); pcAction->setProperty("defaultAction", QVariant(0)); } diff --git a/src/Mod/ReverseEngineering/App/ApproxSurface.cpp b/src/Mod/ReverseEngineering/App/ApproxSurface.cpp index 8dd2dd490..87017200c 100644 --- a/src/Mod/ReverseEngineering/App/ApproxSurface.cpp +++ b/src/Mod/ReverseEngineering/App/ApproxSurface.cpp @@ -45,6 +45,7 @@ using namespace Reen; SplineBasisfunction::SplineBasisfunction(int iSize) : _vKnotVector(0,iSize-1) + , _iOrder(1) { } @@ -557,6 +558,8 @@ ParameterCorrection::ParameterCorrection(unsigned usUOrder, unsigned usVOrder, , _usVOrder(usVOrder) , _usUCtrlpoints(usUCtrlpoints) , _usVCtrlpoints(usVCtrlpoints) + , _pvcPoints(0) + , _pvcUVParam(0) , _vCtrlPntsOfSurf(0,usUCtrlpoints-1,0,usVCtrlpoints-1) , _vUKnots(0,usUCtrlpoints-usUOrder+1) , _vVKnots(0,usVCtrlpoints-usVOrder+1) diff --git a/src/Mod/Robot/App/Trajectory.cpp b/src/Mod/Robot/App/Trajectory.cpp index 2f9950abc..e7310ba05 100644 --- a/src/Mod/Robot/App/Trajectory.cpp +++ b/src/Mod/Robot/App/Trajectory.cpp @@ -55,7 +55,7 @@ using namespace Robot; using namespace Base; //using namespace KDL; - + TYPESYSTEM_SOURCE(Robot::Trajectory , Base::Persistence); @@ -142,13 +142,14 @@ void Trajectory::deleteLast(unsigned int n) } - void Trajectory::generateTrajectory(void) { - if(vpcWaypoints.size()==0)return; + if (vpcWaypoints.size()==0) + return; // delete the old and create a new one - if(pcTrajectory) delete (pcTrajectory); + if (pcTrajectory) + delete (pcTrajectory); pcTrajectory = new KDL::Trajectory_Composite(); // pointer to the pieces while iterating @@ -162,70 +163,72 @@ void Trajectory::generateTrajectory(void) // handle the first waypoint special bool first=true; - for(std::vector::const_iterator it = vpcWaypoints.begin();it!=vpcWaypoints.end();++it){ - if(first){ + for (std::vector::const_iterator it = vpcWaypoints.begin();it!=vpcWaypoints.end();++it) { + if (first) { Last = toFrame((*it)->EndPos); first = false; - }else{ + } + else { // destinct the type of movement switch((*it)->Type){ - case Waypoint::LINE: - case Waypoint::PTP:{ - KDL::Frame Next = toFrame((*it)->EndPos); - // continues the movement until no continus waypoint or the end - bool Cont = (*it)->Cont && !(it==--vpcWaypoints.end()); - // start of a continue block - if(Cont && pcRoundComp==0){ - pcRoundComp = new KDL::Path_RoundedComposite(3, - 3, - new KDL::RotationalInterpolation_SingleAxis() - ); - // the velocity of the first waypoint is used - pcVelPrf = new KDL::VelocityProfile_Trap((*it)->Velocity,(*it)->Accelaration); - pcRoundComp->Add(Last); - pcRoundComp->Add(Next); - - // continue a continues block - }else if (Cont && pcRoundComp){ - pcRoundComp->Add(Next); + case Waypoint::LINE: + case Waypoint::PTP:{ + KDL::Frame Next = toFrame((*it)->EndPos); + // continues the movement until no continus waypoint or the end + bool Cont = (*it)->Cont && !(it==--vpcWaypoints.end()); + // start of a continue block + if (Cont && pcRoundComp==0) { + pcRoundComp = new KDL::Path_RoundedComposite(3, 3, + new KDL::RotationalInterpolation_SingleAxis()); + // the velocity of the first waypoint is used + pcVelPrf = new KDL::VelocityProfile_Trap((*it)->Velocity,(*it)->Accelaration); + pcRoundComp->Add(Last); + pcRoundComp->Add(Next); + // continue a continues block + } + else if (Cont && pcRoundComp) { + pcRoundComp->Add(Next); // end a continous block - }else if (Cont==false && pcRoundComp){ - // add the last one - pcRoundComp->Add(Next); - pcRoundComp->Finish(); - pcVelPrf->SetProfile(0,pcRoundComp->PathLength()); - pcTrak = new KDL::Trajectory_Segment(pcRoundComp,pcVelPrf); - pcRoundComp = 0; + } + else if (Cont==false && pcRoundComp) { + // add the last one + pcRoundComp->Add(Next); + pcRoundComp->Finish(); + pcVelPrf->SetProfile(0,pcRoundComp->PathLength()); + pcTrak = new KDL::Trajectory_Segment(pcRoundComp,pcVelPrf); + pcRoundComp = 0; // normal block - }else if (Cont==false && pcRoundComp==0){ - pcPath = new KDL::Path_Line(Last, - Next, - new KDL::RotationalInterpolation_SingleAxis(), - 1.0, - true - ); - pcVelPrf = new KDL::VelocityProfile_Trap((*it)->Velocity,(*it)->Accelaration); - pcVelPrf->SetProfile(0,pcPath->PathLength()); - pcTrak = new KDL::Trajectory_Segment(pcPath,pcVelPrf); - } - Last = Next; - break;} - case Waypoint::WAIT: - break; - default: - break; + } + else if (Cont==false && pcRoundComp==0){ + pcPath = new KDL::Path_Line(Last, + Next, + new KDL::RotationalInterpolation_SingleAxis(), + 1.0, + true + ); + pcVelPrf = new KDL::VelocityProfile_Trap((*it)->Velocity,(*it)->Accelaration); + pcVelPrf->SetProfile(0,pcPath->PathLength()); + pcTrak = new KDL::Trajectory_Segment(pcPath,pcVelPrf); + } + Last = Next; + break;} + case Waypoint::WAIT: + break; + default: + break; } - // add the segment if no continous block is runing - if(!pcRoundComp) + + // add the segment if no continous block is running + if (!pcRoundComp) pcTrajectory->Add(pcTrak); } } - }catch (KDL::Error &e) { + } + catch (KDL::Error &e) { throw Base::Exception(e.Description()); } - } std::string Trajectory::getUniqueWaypointName(const char *Name) const @@ -322,4 +325,4 @@ void Trajectory::Restore(XMLReader &reader) - + diff --git a/src/Mod/Robot/App/TrajectoryPy.xml b/src/Mod/Robot/App/TrajectoryPy.xml index dfa358a0e..878b29a3a 100644 --- a/src/Mod/Robot/App/TrajectoryPy.xml +++ b/src/Mod/Robot/App/TrajectoryPy.xml @@ -62,9 +62,6 @@ - - bool touched; - diff --git a/src/Mod/Robot/App/TrajectoryPyImp.cpp b/src/Mod/Robot/App/TrajectoryPyImp.cpp index 7ba5d2dc8..55c57cee4 100644 --- a/src/Mod/Robot/App/TrajectoryPyImp.cpp +++ b/src/Mod/Robot/App/TrajectoryPyImp.cpp @@ -28,10 +28,9 @@ #include "Mod/Robot/App/Trajectory.h" // inclusion of the generated files (generated out of TrajectoryPy.xml) -#include "TrajectoryPy.h" -#include "TrajectoryPy.cpp" - -#include "WaypointPy.h" +#include +#include +#include using namespace Robot; diff --git a/src/Mod/Robot/App/Waypoint.cpp b/src/Mod/Robot/App/Waypoint.cpp index fe72e95f4..43108ed57 100644 --- a/src/Mod/Robot/App/Waypoint.cpp +++ b/src/Mod/Robot/App/Waypoint.cpp @@ -56,21 +56,33 @@ using namespace KDL; TYPESYSTEM_SOURCE(Robot::Waypoint , Base::Persistence); -Waypoint::Waypoint( const char* name, - const Base::Placement &endPos, - WaypointType type, - float velocity, - float accelaration, - bool cont, - unsigned int tool, - unsigned int base) +Waypoint::Waypoint(const char* name, + const Base::Placement &endPos, + WaypointType type, + float velocity, + float accelaration, + bool cont, + unsigned int tool, + unsigned int base) -:Name(name),Type(type),Velocity(velocity),Accelaration(accelaration),Cont(cont),Tool(tool),Base(base),EndPos(endPos) + : Name(name) + , Type(type) + , Velocity(velocity) + , Accelaration(accelaration) + , Cont(cont) + , Tool(tool) + , Base(base) + , EndPos(endPos) { } Waypoint::Waypoint() -:Velocity(1000.0),Accelaration(100.0),Cont(false),Tool(0),Base(0) + : Type(UNDEF) + , Velocity(1000.0) + , Accelaration(100.0) + , Cont(false) + , Tool(0) + , Base(0) { } diff --git a/src/Mod/Robot/App/Waypoint.h b/src/Mod/Robot/App/Waypoint.h index 27f475351..8dc8710be 100644 --- a/src/Mod/Robot/App/Waypoint.h +++ b/src/Mod/Robot/App/Waypoint.h @@ -23,10 +23,10 @@ #ifndef ROBOT_WAYPOINT_H #define ROBOT_WAYPOINT_H - + #include "kdl_cp/chain.hpp" #include "kdl_cp/jntarray.hpp" - + #include #include @@ -61,9 +61,9 @@ public: ~Waypoint(); - // from base class + // from base class virtual unsigned int getMemSize (void) const; - virtual void Save (Base::Writer &/*writer*/) const; + virtual void Save (Base::Writer &/*writer*/) const; virtual void Restore(Base::XMLReader &/*reader*/); diff --git a/src/Mod/Robot/Gui/CommandExport.cpp b/src/Mod/Robot/Gui/CommandExport.cpp index 7f6cc2a8e..8eeb0fe12 100644 --- a/src/Mod/Robot/Gui/CommandExport.cpp +++ b/src/Mod/Robot/Gui/CommandExport.cpp @@ -72,17 +72,17 @@ void CmdRobotExportKukaCompact::activated(int iMsg) Robot::RobotObject *pcRobotObject=0; if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId()) - pcRobotObject = dynamic_cast(Sel[0].pObject); + pcRobotObject = static_cast(Sel[0].pObject); else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId()) - pcRobotObject = dynamic_cast(Sel[1].pObject); + pcRobotObject = static_cast(Sel[1].pObject); std::string RoboName = pcRobotObject->getNameInDocument(); Robot::TrajectoryObject *pcTrajectoryObject=0; if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId()) - pcTrajectoryObject = dynamic_cast(Sel[0].pObject); + pcTrajectoryObject = static_cast(Sel[0].pObject); else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId()) - pcTrajectoryObject = dynamic_cast(Sel[1].pObject); - std::string TrakName = pcTrajectoryObject->getNameInDocument(); + pcTrajectoryObject = static_cast(Sel[1].pObject); + //std::string TrakName = pcTrajectoryObject->getNameInDocument(); QStringList filter; filter << QString::fromLatin1("%1 (*.src)").arg(QObject::tr("KRL file")); @@ -134,17 +134,17 @@ void CmdRobotExportKukaFull::activated(int iMsg) Robot::RobotObject *pcRobotObject=0; if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId()) - pcRobotObject = dynamic_cast(Sel[0].pObject); + pcRobotObject = static_cast(Sel[0].pObject); else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId()) - pcRobotObject = dynamic_cast(Sel[1].pObject); - std::string RoboName = pcRobotObject->getNameInDocument(); + pcRobotObject = static_cast(Sel[1].pObject); + //std::string RoboName = pcRobotObject->getNameInDocument(); Robot::TrajectoryObject *pcTrajectoryObject=0; if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId()) - pcTrajectoryObject = dynamic_cast(Sel[0].pObject); + pcTrajectoryObject = static_cast(Sel[0].pObject); else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId()) - pcTrajectoryObject = dynamic_cast(Sel[1].pObject); - std::string TrakName = pcTrajectoryObject->getNameInDocument(); + pcTrajectoryObject = static_cast(Sel[1].pObject); + //std::string TrakName = pcTrajectoryObject->getNameInDocument(); QStringList filter; filter << QString::fromLatin1("%1 (*.src)").arg(QObject::tr("KRL file")); diff --git a/src/Mod/Robot/Gui/CommandTrajectory.cpp b/src/Mod/Robot/Gui/CommandTrajectory.cpp index f95aa99bc..da1eeaaa2 100644 --- a/src/Mod/Robot/Gui/CommandTrajectory.cpp +++ b/src/Mod/Robot/Gui/CommandTrajectory.cpp @@ -117,16 +117,16 @@ void CmdRobotInsertWaypoint::activated(int iMsg) Robot::RobotObject *pcRobotObject=0; if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId()) - pcRobotObject = dynamic_cast(Sel[0].pObject); + pcRobotObject = static_cast(Sel[0].pObject); else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId()) - pcRobotObject = dynamic_cast(Sel[1].pObject); + pcRobotObject = static_cast(Sel[1].pObject); std::string RoboName = pcRobotObject->getNameInDocument(); Robot::TrajectoryObject *pcTrajectoryObject=0; if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId()) - pcTrajectoryObject = dynamic_cast(Sel[0].pObject); + pcTrajectoryObject = static_cast(Sel[0].pObject); else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId()) - pcTrajectoryObject = dynamic_cast(Sel[1].pObject); + pcTrajectoryObject = static_cast(Sel[1].pObject); std::string TrakName = pcTrajectoryObject->getNameInDocument(); openCommand("Insert waypoint"); @@ -179,7 +179,7 @@ void CmdRobotInsertWaypointPreselect::activated(int iMsg) Robot::TrajectoryObject *pcTrajectoryObject; if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId()) - pcTrajectoryObject = dynamic_cast(Sel[0].pObject); + pcTrajectoryObject = static_cast(Sel[0].pObject); else { QMessageBox::warning(Gui::getMainWindow(), QObject::tr("Wrong selection"), QObject::tr("Select one Trajectory object.")); diff --git a/src/Mod/Robot/Gui/TrajectorySimulate.cpp b/src/Mod/Robot/Gui/TrajectorySimulate.cpp index fae228ed8..a2a09596a 100644 --- a/src/Mod/Robot/Gui/TrajectorySimulate.cpp +++ b/src/Mod/Robot/Gui/TrajectorySimulate.cpp @@ -98,7 +98,7 @@ TrajectorySimulate::TrajectorySimulate(Robot::RobotObject *pcRobotObject,Robot:: QObject::connect( timeSlider ,SIGNAL(valueChanged(int) ), this, SLOT(valueChanged(int)) ); // get the view provider - ViewProv = dynamic_cast(Gui::Application::Instance->activeDocument()->getViewProvider(pcRobotObject) ); + ViewProv = static_cast(Gui::Application::Instance->activeDocument()->getViewProvider(pcRobotObject) ); setTo(); } diff --git a/src/Mod/Robot/Gui/ViewProviderEdge2TracObject.cpp b/src/Mod/Robot/Gui/ViewProviderEdge2TracObject.cpp index e4eac3e03..b529c36c7 100644 --- a/src/Mod/Robot/Gui/ViewProviderEdge2TracObject.cpp +++ b/src/Mod/Robot/Gui/ViewProviderEdge2TracObject.cpp @@ -37,7 +37,7 @@ PROPERTY_SOURCE(RobotGui::ViewProviderEdge2TracObject, RobotGui::ViewProviderTra bool ViewProviderEdge2TracObject::doubleClicked(void) { - Gui::TaskView::TaskDialog* dlg = new TaskDlgEdge2Trac(dynamic_cast(getObject())); + Gui::TaskView::TaskDialog* dlg = new TaskDlgEdge2Trac(static_cast(getObject())); Gui::Control().showDialog(dlg); return true; } @@ -45,7 +45,7 @@ bool ViewProviderEdge2TracObject::doubleClicked(void) bool ViewProviderEdge2TracObject::setEdit(int ModNum) { - Gui::TaskView::TaskDialog* dlg = new TaskDlgEdge2Trac(dynamic_cast(getObject())); + Gui::TaskView::TaskDialog* dlg = new TaskDlgEdge2Trac(static_cast(getObject())); Gui::Control().showDialog(dlg); return true; } diff --git a/src/Mod/Robot/Gui/ViewProviderRobotObject.h b/src/Mod/Robot/Gui/ViewProviderRobotObject.h index 69d7e8f29..80c1a31de 100644 --- a/src/Mod/Robot/Gui/ViewProviderRobotObject.h +++ b/src/Mod/Robot/Gui/ViewProviderRobotObject.h @@ -52,26 +52,26 @@ public: void attach(App::DocumentObject *pcObject); void setDisplayMode(const char* ModeName); std::vector getDisplayModes() const; - void updateData(const App::Property*); - - virtual void onChanged(const App::Property* prop); - - /// for simulation without changing the document: - void setAxisTo(float A1,float A2,float A3,float A4,float A5,float A6,const Base::Placement &Tcp); - -protected: - static void sDraggerMotionCallback(void *data, SoDragger *dragger); - void DraggerMotionCallback(SoDragger *dragger); - - void setDragger(void); - void resetDragger(void); - + void updateData(const App::Property*); + + virtual void onChanged(const App::Property* prop); + + /// for simulation without changing the document: + void setAxisTo(float A1,float A2,float A3,float A4,float A5,float A6,const Base::Placement &Tcp); + +protected: + static void sDraggerMotionCallback(void *data, SoDragger *dragger); + void DraggerMotionCallback(SoDragger *dragger); + + void setDragger(void); + void resetDragger(void); + Gui::SoFCSelection * pcRobotRoot; Gui::SoFCSelection * pcSimpleRoot; SoGroup * pcOffRoot; SoGroup * pcTcpRoot; - SoTransform * pcTcpTransform; + //SoTransform * pcTcpTransform; //SoTrackballDragger * pcDragger; SoJackDragger * pcDragger; diff --git a/src/Mod/Robot/Gui/ViewProviderTrajectoryDressUp.cpp b/src/Mod/Robot/Gui/ViewProviderTrajectoryDressUp.cpp index edc7f7df7..f539f3c8d 100644 --- a/src/Mod/Robot/Gui/ViewProviderTrajectoryDressUp.cpp +++ b/src/Mod/Robot/Gui/ViewProviderTrajectoryDressUp.cpp @@ -45,7 +45,7 @@ PROPERTY_SOURCE(RobotGui::ViewProviderTrajectoryDressUp, RobotGui::ViewProviderT bool ViewProviderTrajectoryDressUp::setEdit(int ModNum) { - Gui::TaskView::TaskDialog* dlg = new TaskDlgTrajectoryDressUp(dynamic_cast(getObject())); + Gui::TaskView::TaskDialog* dlg = new TaskDlgTrajectoryDressUp(static_cast(getObject())); Gui::Control().showDialog(dlg); return true; } diff --git a/src/Mod/Sketcher/Gui/TaskSketcherValidation.cpp b/src/Mod/Sketcher/Gui/TaskSketcherValidation.cpp index 828760935..dea9357ba 100644 --- a/src/Mod/Sketcher/Gui/TaskSketcherValidation.cpp +++ b/src/Mod/Sketcher/Gui/TaskSketcherValidation.cpp @@ -186,7 +186,7 @@ void SketcherValidation::on_findButton_clicked() for (std::size_t i=0; igetTypeId() == Part::GeomLineSegment::getClassTypeId()) { - const Part::GeomLineSegment *segm = dynamic_cast(g); + const Part::GeomLineSegment *segm = static_cast(g); VertexIds id; id.GeoId = (int)i; id.PosId = Sketcher::start; @@ -198,7 +198,7 @@ void SketcherValidation::on_findButton_clicked() vertexIds.push_back(id); } else if (g->getTypeId() == Part::GeomArcOfCircle::getClassTypeId()) { - const Part::GeomArcOfCircle *segm = dynamic_cast(g); + const Part::GeomArcOfCircle *segm = static_cast(g); VertexIds id; id.GeoId = (int)i; id.PosId = Sketcher::start; @@ -210,7 +210,7 @@ void SketcherValidation::on_findButton_clicked() vertexIds.push_back(id); } else if (g->getTypeId() == Part::GeomArcOfEllipse::getClassTypeId()) { - const Part::GeomArcOfEllipse *segm = dynamic_cast(g); + const Part::GeomArcOfEllipse *segm = static_cast(g); VertexIds id; id.GeoId = (int)i; id.PosId = Sketcher::start; @@ -375,7 +375,7 @@ void SketcherValidation::on_findReversed_clicked() Part::Geometry* g = geom[i]; //only arcs of circles need to be repaired. Arcs of ellipse were so broken there should be nothing to repair from. if (g->getTypeId() == Part::GeomArcOfCircle::getClassTypeId()) { - const Part::GeomArcOfCircle *segm = dynamic_cast(g); + const Part::GeomArcOfCircle *segm = static_cast(g); if(segm->isReversedInXY()){ points.push_back(segm->getStartPoint(/*emulateCCW=*/true)); points.push_back(segm->getEndPoint(/*emulateCCW=*/true)); diff --git a/src/Mod/Sketcher/Gui/ViewProviderSketch.h b/src/Mod/Sketcher/Gui/ViewProviderSketch.h index 01d8c3896..5752bc123 100644 --- a/src/Mod/Sketcher/Gui/ViewProviderSketch.h +++ b/src/Mod/Sketcher/Gui/ViewProviderSketch.h @@ -393,7 +393,6 @@ protected: bool relative; std::string oldWb; - int antiAliasing; Gui::Rubberband* rubberband; App::Part* parentPart = nullptr; diff --git a/src/Mod/Web/App/AppWeb.cpp b/src/Mod/Web/App/AppWeb.cpp index 07f7a3f53..6461af5f1 100644 --- a/src/Mod/Web/App/AppWeb.cpp +++ b/src/Mod/Web/App/AppWeb.cpp @@ -108,8 +108,6 @@ private: out << "Server failed to listen at address " << addr << " and port " << port; throw Py::RuntimeError(out.str()); } - - return Py::None(); } Py::Object registerServerFirewall(const Py::Tuple& args)