fix Coverity issues
This commit is contained in:
parent
ae663b3b51
commit
d80c05e186
|
@ -105,7 +105,7 @@ App::DocumentObjectExecReturn *LuxProject::execute(void)
|
||||||
const std::vector<App::DocumentObject*> &Grp = Group.getValues();
|
const std::vector<App::DocumentObject*> &Grp = Group.getValues();
|
||||||
for (std::vector<App::DocumentObject*>::const_iterator It= Grp.begin();It!=Grp.end();++It) {
|
for (std::vector<App::DocumentObject*>::const_iterator It= Grp.begin();It!=Grp.end();++It) {
|
||||||
if ((*It)->getTypeId().isDerivedFrom(Raytracing::RaySegment::getClassTypeId())) {
|
if ((*It)->getTypeId().isDerivedFrom(Raytracing::RaySegment::getClassTypeId())) {
|
||||||
Raytracing::RaySegment *View = dynamic_cast<Raytracing::RaySegment *>(*It);
|
Raytracing::RaySegment *View = static_cast<Raytracing::RaySegment *>(*It);
|
||||||
ofile << View->Result.getValue();
|
ofile << View->Result.getValue();
|
||||||
ofile << endl;
|
ofile << endl;
|
||||||
}
|
}
|
||||||
|
|
|
@ -99,7 +99,7 @@ App::DocumentObjectExecReturn *RayProject::execute(void)
|
||||||
const std::vector<App::DocumentObject*> &Grp = Group.getValues();
|
const std::vector<App::DocumentObject*> &Grp = Group.getValues();
|
||||||
for (std::vector<App::DocumentObject*>::const_iterator It= Grp.begin();It!=Grp.end();++It) {
|
for (std::vector<App::DocumentObject*>::const_iterator It= Grp.begin();It!=Grp.end();++It) {
|
||||||
if ((*It)->getTypeId().isDerivedFrom(Raytracing::RaySegment::getClassTypeId())) {
|
if ((*It)->getTypeId().isDerivedFrom(Raytracing::RaySegment::getClassTypeId())) {
|
||||||
Raytracing::RaySegment *View = dynamic_cast<Raytracing::RaySegment *>(*It);
|
Raytracing::RaySegment *View = static_cast<Raytracing::RaySegment *>(*It);
|
||||||
ofile << View->Result.getValue();
|
ofile << View->Result.getValue();
|
||||||
ofile << endl << endl << endl;
|
ofile << endl << endl << endl;
|
||||||
}
|
}
|
||||||
|
|
|
@ -369,9 +369,6 @@ Gui::Action * CmdRaytracingNewPovrayProject::createAction(void)
|
||||||
pcAction->setDropDownMenu(true);
|
pcAction->setDropDownMenu(true);
|
||||||
applyCommandData(this->className(), pcAction);
|
applyCommandData(this->className(), pcAction);
|
||||||
|
|
||||||
QAction* defaultAction = 0;
|
|
||||||
int defaultId = 0;
|
|
||||||
|
|
||||||
std::string path = App::Application::getResourceDir();
|
std::string path = App::Application::getResourceDir();
|
||||||
path += "Mod/Raytracing/Templates/";
|
path += "Mod/Raytracing/Templates/";
|
||||||
QDir dir(QString::fromUtf8(path.c_str()), QString::fromLatin1("*.pov"));
|
QDir dir(QString::fromUtf8(path.c_str()), QString::fromLatin1("*.pov"));
|
||||||
|
@ -385,11 +382,7 @@ Gui::Action * CmdRaytracingNewPovrayProject::createAction(void)
|
||||||
|
|
||||||
_pcAction = pcAction;
|
_pcAction = pcAction;
|
||||||
languageChange();
|
languageChange();
|
||||||
if (defaultAction) {
|
if (!pcAction->actions().isEmpty()) {
|
||||||
pcAction->setIcon(defaultAction->icon());
|
|
||||||
pcAction->setProperty("defaultAction", QVariant(defaultId));
|
|
||||||
}
|
|
||||||
else if (!pcAction->actions().isEmpty()) {
|
|
||||||
pcAction->setIcon(pcAction->actions()[0]->icon());
|
pcAction->setIcon(pcAction->actions()[0]->icon());
|
||||||
pcAction->setProperty("defaultAction", QVariant(0));
|
pcAction->setProperty("defaultAction", QVariant(0));
|
||||||
}
|
}
|
||||||
|
@ -767,9 +760,6 @@ Gui::Action * CmdRaytracingNewLuxProject::createAction(void)
|
||||||
pcAction->setDropDownMenu(true);
|
pcAction->setDropDownMenu(true);
|
||||||
applyCommandData(this->className(), pcAction);
|
applyCommandData(this->className(), pcAction);
|
||||||
|
|
||||||
QAction* defaultAction = 0;
|
|
||||||
int defaultId = 0;
|
|
||||||
|
|
||||||
std::string path = App::Application::getResourceDir();
|
std::string path = App::Application::getResourceDir();
|
||||||
path += "Mod/Raytracing/Templates/";
|
path += "Mod/Raytracing/Templates/";
|
||||||
QDir dir(QString::fromUtf8(path.c_str()), QString::fromLatin1("*.lxs"));
|
QDir dir(QString::fromUtf8(path.c_str()), QString::fromLatin1("*.lxs"));
|
||||||
|
@ -783,11 +773,7 @@ Gui::Action * CmdRaytracingNewLuxProject::createAction(void)
|
||||||
|
|
||||||
_pcAction = pcAction;
|
_pcAction = pcAction;
|
||||||
languageChange();
|
languageChange();
|
||||||
if (defaultAction) {
|
if (!pcAction->actions().isEmpty()) {
|
||||||
pcAction->setIcon(defaultAction->icon());
|
|
||||||
pcAction->setProperty("defaultAction", QVariant(defaultId));
|
|
||||||
}
|
|
||||||
else if (!pcAction->actions().isEmpty()) {
|
|
||||||
pcAction->setIcon(pcAction->actions()[0]->icon());
|
pcAction->setIcon(pcAction->actions()[0]->icon());
|
||||||
pcAction->setProperty("defaultAction", QVariant(0));
|
pcAction->setProperty("defaultAction", QVariant(0));
|
||||||
}
|
}
|
||||||
|
|
|
@ -45,6 +45,7 @@ using namespace Reen;
|
||||||
|
|
||||||
SplineBasisfunction::SplineBasisfunction(int iSize)
|
SplineBasisfunction::SplineBasisfunction(int iSize)
|
||||||
: _vKnotVector(0,iSize-1)
|
: _vKnotVector(0,iSize-1)
|
||||||
|
, _iOrder(1)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -557,6 +558,8 @@ ParameterCorrection::ParameterCorrection(unsigned usUOrder, unsigned usVOrder,
|
||||||
, _usVOrder(usVOrder)
|
, _usVOrder(usVOrder)
|
||||||
, _usUCtrlpoints(usUCtrlpoints)
|
, _usUCtrlpoints(usUCtrlpoints)
|
||||||
, _usVCtrlpoints(usVCtrlpoints)
|
, _usVCtrlpoints(usVCtrlpoints)
|
||||||
|
, _pvcPoints(0)
|
||||||
|
, _pvcUVParam(0)
|
||||||
, _vCtrlPntsOfSurf(0,usUCtrlpoints-1,0,usVCtrlpoints-1)
|
, _vCtrlPntsOfSurf(0,usUCtrlpoints-1,0,usVCtrlpoints-1)
|
||||||
, _vUKnots(0,usUCtrlpoints-usUOrder+1)
|
, _vUKnots(0,usUCtrlpoints-usUOrder+1)
|
||||||
, _vVKnots(0,usVCtrlpoints-usVOrder+1)
|
, _vVKnots(0,usVCtrlpoints-usVOrder+1)
|
||||||
|
|
|
@ -142,13 +142,14 @@ void Trajectory::deleteLast(unsigned int n)
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void Trajectory::generateTrajectory(void)
|
void Trajectory::generateTrajectory(void)
|
||||||
{
|
{
|
||||||
if(vpcWaypoints.size()==0)return;
|
if (vpcWaypoints.size()==0)
|
||||||
|
return;
|
||||||
|
|
||||||
// delete the old and create a new one
|
// delete the old and create a new one
|
||||||
if(pcTrajectory) delete (pcTrajectory);
|
if (pcTrajectory)
|
||||||
|
delete (pcTrajectory);
|
||||||
pcTrajectory = new KDL::Trajectory_Composite();
|
pcTrajectory = new KDL::Trajectory_Composite();
|
||||||
|
|
||||||
// pointer to the pieces while iterating
|
// pointer to the pieces while iterating
|
||||||
|
@ -162,70 +163,72 @@ void Trajectory::generateTrajectory(void)
|
||||||
// handle the first waypoint special
|
// handle the first waypoint special
|
||||||
bool first=true;
|
bool first=true;
|
||||||
|
|
||||||
for(std::vector<Waypoint*>::const_iterator it = vpcWaypoints.begin();it!=vpcWaypoints.end();++it){
|
for (std::vector<Waypoint*>::const_iterator it = vpcWaypoints.begin();it!=vpcWaypoints.end();++it) {
|
||||||
if(first){
|
if (first) {
|
||||||
Last = toFrame((*it)->EndPos);
|
Last = toFrame((*it)->EndPos);
|
||||||
first = false;
|
first = false;
|
||||||
}else{
|
}
|
||||||
|
else {
|
||||||
// destinct the type of movement
|
// destinct the type of movement
|
||||||
switch((*it)->Type){
|
switch((*it)->Type){
|
||||||
case Waypoint::LINE:
|
case Waypoint::LINE:
|
||||||
case Waypoint::PTP:{
|
case Waypoint::PTP:{
|
||||||
KDL::Frame Next = toFrame((*it)->EndPos);
|
KDL::Frame Next = toFrame((*it)->EndPos);
|
||||||
// continues the movement until no continus waypoint or the end
|
// continues the movement until no continus waypoint or the end
|
||||||
bool Cont = (*it)->Cont && !(it==--vpcWaypoints.end());
|
bool Cont = (*it)->Cont && !(it==--vpcWaypoints.end());
|
||||||
// start of a continue block
|
// start of a continue block
|
||||||
if(Cont && pcRoundComp==0){
|
if (Cont && pcRoundComp==0) {
|
||||||
pcRoundComp = new KDL::Path_RoundedComposite(3,
|
pcRoundComp = new KDL::Path_RoundedComposite(3, 3,
|
||||||
3,
|
new KDL::RotationalInterpolation_SingleAxis());
|
||||||
new KDL::RotationalInterpolation_SingleAxis()
|
// the velocity of the first waypoint is used
|
||||||
);
|
pcVelPrf = new KDL::VelocityProfile_Trap((*it)->Velocity,(*it)->Accelaration);
|
||||||
// the velocity of the first waypoint is used
|
pcRoundComp->Add(Last);
|
||||||
pcVelPrf = new KDL::VelocityProfile_Trap((*it)->Velocity,(*it)->Accelaration);
|
pcRoundComp->Add(Next);
|
||||||
pcRoundComp->Add(Last);
|
|
||||||
pcRoundComp->Add(Next);
|
|
||||||
|
|
||||||
// continue a continues block
|
|
||||||
}else if (Cont && pcRoundComp){
|
|
||||||
pcRoundComp->Add(Next);
|
|
||||||
|
|
||||||
|
// continue a continues block
|
||||||
|
}
|
||||||
|
else if (Cont && pcRoundComp) {
|
||||||
|
pcRoundComp->Add(Next);
|
||||||
// end a continous block
|
// end a continous block
|
||||||
}else if (Cont==false && pcRoundComp){
|
}
|
||||||
// add the last one
|
else if (Cont==false && pcRoundComp) {
|
||||||
pcRoundComp->Add(Next);
|
// add the last one
|
||||||
pcRoundComp->Finish();
|
pcRoundComp->Add(Next);
|
||||||
pcVelPrf->SetProfile(0,pcRoundComp->PathLength());
|
pcRoundComp->Finish();
|
||||||
pcTrak = new KDL::Trajectory_Segment(pcRoundComp,pcVelPrf);
|
pcVelPrf->SetProfile(0,pcRoundComp->PathLength());
|
||||||
pcRoundComp = 0;
|
pcTrak = new KDL::Trajectory_Segment(pcRoundComp,pcVelPrf);
|
||||||
|
pcRoundComp = 0;
|
||||||
|
|
||||||
// normal block
|
// normal block
|
||||||
}else if (Cont==false && pcRoundComp==0){
|
}
|
||||||
pcPath = new KDL::Path_Line(Last,
|
else if (Cont==false && pcRoundComp==0){
|
||||||
Next,
|
pcPath = new KDL::Path_Line(Last,
|
||||||
new KDL::RotationalInterpolation_SingleAxis(),
|
Next,
|
||||||
1.0,
|
new KDL::RotationalInterpolation_SingleAxis(),
|
||||||
true
|
1.0,
|
||||||
);
|
true
|
||||||
pcVelPrf = new KDL::VelocityProfile_Trap((*it)->Velocity,(*it)->Accelaration);
|
);
|
||||||
pcVelPrf->SetProfile(0,pcPath->PathLength());
|
pcVelPrf = new KDL::VelocityProfile_Trap((*it)->Velocity,(*it)->Accelaration);
|
||||||
pcTrak = new KDL::Trajectory_Segment(pcPath,pcVelPrf);
|
pcVelPrf->SetProfile(0,pcPath->PathLength());
|
||||||
}
|
pcTrak = new KDL::Trajectory_Segment(pcPath,pcVelPrf);
|
||||||
Last = Next;
|
}
|
||||||
break;}
|
Last = Next;
|
||||||
case Waypoint::WAIT:
|
break;}
|
||||||
break;
|
case Waypoint::WAIT:
|
||||||
default:
|
break;
|
||||||
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);
|
pcTrajectory->Add(pcTrak);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}catch (KDL::Error &e) {
|
}
|
||||||
|
catch (KDL::Error &e) {
|
||||||
throw Base::Exception(e.Description());
|
throw Base::Exception(e.Description());
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string Trajectory::getUniqueWaypointName(const char *Name) const
|
std::string Trajectory::getUniqueWaypointName(const char *Name) const
|
||||||
|
|
|
@ -62,9 +62,6 @@
|
||||||
</Documentation>
|
</Documentation>
|
||||||
<Parameter Name="Waypoints" Type="List"/>
|
<Parameter Name="Waypoints" Type="List"/>
|
||||||
</Attribute>
|
</Attribute>
|
||||||
<ClassDeclarations>
|
|
||||||
bool touched;
|
|
||||||
</ClassDeclarations>
|
|
||||||
|
|
||||||
</PythonExport>
|
</PythonExport>
|
||||||
</GenerateModel>
|
</GenerateModel>
|
||||||
|
|
|
@ -28,10 +28,9 @@
|
||||||
#include "Mod/Robot/App/Trajectory.h"
|
#include "Mod/Robot/App/Trajectory.h"
|
||||||
|
|
||||||
// inclusion of the generated files (generated out of TrajectoryPy.xml)
|
// inclusion of the generated files (generated out of TrajectoryPy.xml)
|
||||||
#include "TrajectoryPy.h"
|
#include <Mod/Robot/App/TrajectoryPy.h>
|
||||||
#include "TrajectoryPy.cpp"
|
#include <Mod/Robot/App/TrajectoryPy.cpp>
|
||||||
|
#include <Mod/Robot/App/WaypointPy.h>
|
||||||
#include "WaypointPy.h"
|
|
||||||
|
|
||||||
using namespace Robot;
|
using namespace Robot;
|
||||||
|
|
||||||
|
|
|
@ -56,21 +56,33 @@ using namespace KDL;
|
||||||
|
|
||||||
TYPESYSTEM_SOURCE(Robot::Waypoint , Base::Persistence);
|
TYPESYSTEM_SOURCE(Robot::Waypoint , Base::Persistence);
|
||||||
|
|
||||||
Waypoint::Waypoint( const char* name,
|
Waypoint::Waypoint(const char* name,
|
||||||
const Base::Placement &endPos,
|
const Base::Placement &endPos,
|
||||||
WaypointType type,
|
WaypointType type,
|
||||||
float velocity,
|
float velocity,
|
||||||
float accelaration,
|
float accelaration,
|
||||||
bool cont,
|
bool cont,
|
||||||
unsigned int tool,
|
unsigned int tool,
|
||||||
unsigned int base)
|
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()
|
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)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -61,9 +61,9 @@ public:
|
||||||
|
|
||||||
~Waypoint();
|
~Waypoint();
|
||||||
|
|
||||||
// from base class
|
// from base class
|
||||||
virtual unsigned int getMemSize (void) const;
|
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*/);
|
virtual void Restore(Base::XMLReader &/*reader*/);
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -72,17 +72,17 @@ void CmdRobotExportKukaCompact::activated(int iMsg)
|
||||||
|
|
||||||
Robot::RobotObject *pcRobotObject=0;
|
Robot::RobotObject *pcRobotObject=0;
|
||||||
if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
||||||
pcRobotObject = dynamic_cast<Robot::RobotObject*>(Sel[0].pObject);
|
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[0].pObject);
|
||||||
else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
||||||
pcRobotObject = dynamic_cast<Robot::RobotObject*>(Sel[1].pObject);
|
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[1].pObject);
|
||||||
std::string RoboName = pcRobotObject->getNameInDocument();
|
std::string RoboName = pcRobotObject->getNameInDocument();
|
||||||
|
|
||||||
Robot::TrajectoryObject *pcTrajectoryObject=0;
|
Robot::TrajectoryObject *pcTrajectoryObject=0;
|
||||||
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
||||||
pcTrajectoryObject = dynamic_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
|
pcTrajectoryObject = static_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
|
||||||
else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
||||||
pcTrajectoryObject = dynamic_cast<Robot::TrajectoryObject*>(Sel[1].pObject);
|
pcTrajectoryObject = static_cast<Robot::TrajectoryObject*>(Sel[1].pObject);
|
||||||
std::string TrakName = pcTrajectoryObject->getNameInDocument();
|
//std::string TrakName = pcTrajectoryObject->getNameInDocument();
|
||||||
|
|
||||||
QStringList filter;
|
QStringList filter;
|
||||||
filter << QString::fromLatin1("%1 (*.src)").arg(QObject::tr("KRL file"));
|
filter << QString::fromLatin1("%1 (*.src)").arg(QObject::tr("KRL file"));
|
||||||
|
@ -134,17 +134,17 @@ void CmdRobotExportKukaFull::activated(int iMsg)
|
||||||
|
|
||||||
Robot::RobotObject *pcRobotObject=0;
|
Robot::RobotObject *pcRobotObject=0;
|
||||||
if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
||||||
pcRobotObject = dynamic_cast<Robot::RobotObject*>(Sel[0].pObject);
|
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[0].pObject);
|
||||||
else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
||||||
pcRobotObject = dynamic_cast<Robot::RobotObject*>(Sel[1].pObject);
|
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[1].pObject);
|
||||||
std::string RoboName = pcRobotObject->getNameInDocument();
|
//std::string RoboName = pcRobotObject->getNameInDocument();
|
||||||
|
|
||||||
Robot::TrajectoryObject *pcTrajectoryObject=0;
|
Robot::TrajectoryObject *pcTrajectoryObject=0;
|
||||||
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
||||||
pcTrajectoryObject = dynamic_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
|
pcTrajectoryObject = static_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
|
||||||
else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
||||||
pcTrajectoryObject = dynamic_cast<Robot::TrajectoryObject*>(Sel[1].pObject);
|
pcTrajectoryObject = static_cast<Robot::TrajectoryObject*>(Sel[1].pObject);
|
||||||
std::string TrakName = pcTrajectoryObject->getNameInDocument();
|
//std::string TrakName = pcTrajectoryObject->getNameInDocument();
|
||||||
|
|
||||||
QStringList filter;
|
QStringList filter;
|
||||||
filter << QString::fromLatin1("%1 (*.src)").arg(QObject::tr("KRL file"));
|
filter << QString::fromLatin1("%1 (*.src)").arg(QObject::tr("KRL file"));
|
||||||
|
|
|
@ -117,16 +117,16 @@ void CmdRobotInsertWaypoint::activated(int iMsg)
|
||||||
|
|
||||||
Robot::RobotObject *pcRobotObject=0;
|
Robot::RobotObject *pcRobotObject=0;
|
||||||
if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
||||||
pcRobotObject = dynamic_cast<Robot::RobotObject*>(Sel[0].pObject);
|
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[0].pObject);
|
||||||
else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
|
||||||
pcRobotObject = dynamic_cast<Robot::RobotObject*>(Sel[1].pObject);
|
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[1].pObject);
|
||||||
std::string RoboName = pcRobotObject->getNameInDocument();
|
std::string RoboName = pcRobotObject->getNameInDocument();
|
||||||
|
|
||||||
Robot::TrajectoryObject *pcTrajectoryObject=0;
|
Robot::TrajectoryObject *pcTrajectoryObject=0;
|
||||||
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
||||||
pcTrajectoryObject = dynamic_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
|
pcTrajectoryObject = static_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
|
||||||
else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
||||||
pcTrajectoryObject = dynamic_cast<Robot::TrajectoryObject*>(Sel[1].pObject);
|
pcTrajectoryObject = static_cast<Robot::TrajectoryObject*>(Sel[1].pObject);
|
||||||
std::string TrakName = pcTrajectoryObject->getNameInDocument();
|
std::string TrakName = pcTrajectoryObject->getNameInDocument();
|
||||||
|
|
||||||
openCommand("Insert waypoint");
|
openCommand("Insert waypoint");
|
||||||
|
@ -179,7 +179,7 @@ void CmdRobotInsertWaypointPreselect::activated(int iMsg)
|
||||||
|
|
||||||
Robot::TrajectoryObject *pcTrajectoryObject;
|
Robot::TrajectoryObject *pcTrajectoryObject;
|
||||||
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
|
||||||
pcTrajectoryObject = dynamic_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
|
pcTrajectoryObject = static_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
|
||||||
else {
|
else {
|
||||||
QMessageBox::warning(Gui::getMainWindow(), QObject::tr("Wrong selection"),
|
QMessageBox::warning(Gui::getMainWindow(), QObject::tr("Wrong selection"),
|
||||||
QObject::tr("Select one Trajectory object."));
|
QObject::tr("Select one Trajectory object."));
|
||||||
|
|
|
@ -98,7 +98,7 @@ TrajectorySimulate::TrajectorySimulate(Robot::RobotObject *pcRobotObject,Robot::
|
||||||
QObject::connect( timeSlider ,SIGNAL(valueChanged(int) ), this, SLOT(valueChanged(int)) );
|
QObject::connect( timeSlider ,SIGNAL(valueChanged(int) ), this, SLOT(valueChanged(int)) );
|
||||||
|
|
||||||
// get the view provider
|
// get the view provider
|
||||||
ViewProv = dynamic_cast<ViewProviderRobotObject*>(Gui::Application::Instance->activeDocument()->getViewProvider(pcRobotObject) );
|
ViewProv = static_cast<ViewProviderRobotObject*>(Gui::Application::Instance->activeDocument()->getViewProvider(pcRobotObject) );
|
||||||
|
|
||||||
setTo();
|
setTo();
|
||||||
}
|
}
|
||||||
|
|
|
@ -37,7 +37,7 @@ PROPERTY_SOURCE(RobotGui::ViewProviderEdge2TracObject, RobotGui::ViewProviderTra
|
||||||
|
|
||||||
bool ViewProviderEdge2TracObject::doubleClicked(void)
|
bool ViewProviderEdge2TracObject::doubleClicked(void)
|
||||||
{
|
{
|
||||||
Gui::TaskView::TaskDialog* dlg = new TaskDlgEdge2Trac(dynamic_cast<Robot::Edge2TracObject *>(getObject()));
|
Gui::TaskView::TaskDialog* dlg = new TaskDlgEdge2Trac(static_cast<Robot::Edge2TracObject *>(getObject()));
|
||||||
Gui::Control().showDialog(dlg);
|
Gui::Control().showDialog(dlg);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -45,7 +45,7 @@ bool ViewProviderEdge2TracObject::doubleClicked(void)
|
||||||
|
|
||||||
bool ViewProviderEdge2TracObject::setEdit(int ModNum)
|
bool ViewProviderEdge2TracObject::setEdit(int ModNum)
|
||||||
{
|
{
|
||||||
Gui::TaskView::TaskDialog* dlg = new TaskDlgEdge2Trac(dynamic_cast<Robot::Edge2TracObject *>(getObject()));
|
Gui::TaskView::TaskDialog* dlg = new TaskDlgEdge2Trac(static_cast<Robot::Edge2TracObject *>(getObject()));
|
||||||
Gui::Control().showDialog(dlg);
|
Gui::Control().showDialog(dlg);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -71,7 +71,7 @@ protected:
|
||||||
SoGroup * pcOffRoot;
|
SoGroup * pcOffRoot;
|
||||||
|
|
||||||
SoGroup * pcTcpRoot;
|
SoGroup * pcTcpRoot;
|
||||||
SoTransform * pcTcpTransform;
|
//SoTransform * pcTcpTransform;
|
||||||
|
|
||||||
//SoTrackballDragger * pcDragger;
|
//SoTrackballDragger * pcDragger;
|
||||||
SoJackDragger * pcDragger;
|
SoJackDragger * pcDragger;
|
||||||
|
|
|
@ -45,7 +45,7 @@ PROPERTY_SOURCE(RobotGui::ViewProviderTrajectoryDressUp, RobotGui::ViewProviderT
|
||||||
|
|
||||||
bool ViewProviderTrajectoryDressUp::setEdit(int ModNum)
|
bool ViewProviderTrajectoryDressUp::setEdit(int ModNum)
|
||||||
{
|
{
|
||||||
Gui::TaskView::TaskDialog* dlg = new TaskDlgTrajectoryDressUp(dynamic_cast<Robot::TrajectoryDressUpObject *>(getObject()));
|
Gui::TaskView::TaskDialog* dlg = new TaskDlgTrajectoryDressUp(static_cast<Robot::TrajectoryDressUpObject *>(getObject()));
|
||||||
Gui::Control().showDialog(dlg);
|
Gui::Control().showDialog(dlg);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -186,7 +186,7 @@ void SketcherValidation::on_findButton_clicked()
|
||||||
for (std::size_t i=0; i<geom.size(); i++) {
|
for (std::size_t i=0; i<geom.size(); i++) {
|
||||||
Part::Geometry* g = geom[i];
|
Part::Geometry* g = geom[i];
|
||||||
if (g->getTypeId() == Part::GeomLineSegment::getClassTypeId()) {
|
if (g->getTypeId() == Part::GeomLineSegment::getClassTypeId()) {
|
||||||
const Part::GeomLineSegment *segm = dynamic_cast<const Part::GeomLineSegment*>(g);
|
const Part::GeomLineSegment *segm = static_cast<const Part::GeomLineSegment*>(g);
|
||||||
VertexIds id;
|
VertexIds id;
|
||||||
id.GeoId = (int)i;
|
id.GeoId = (int)i;
|
||||||
id.PosId = Sketcher::start;
|
id.PosId = Sketcher::start;
|
||||||
|
@ -198,7 +198,7 @@ void SketcherValidation::on_findButton_clicked()
|
||||||
vertexIds.push_back(id);
|
vertexIds.push_back(id);
|
||||||
}
|
}
|
||||||
else if (g->getTypeId() == Part::GeomArcOfCircle::getClassTypeId()) {
|
else if (g->getTypeId() == Part::GeomArcOfCircle::getClassTypeId()) {
|
||||||
const Part::GeomArcOfCircle *segm = dynamic_cast<const Part::GeomArcOfCircle*>(g);
|
const Part::GeomArcOfCircle *segm = static_cast<const Part::GeomArcOfCircle*>(g);
|
||||||
VertexIds id;
|
VertexIds id;
|
||||||
id.GeoId = (int)i;
|
id.GeoId = (int)i;
|
||||||
id.PosId = Sketcher::start;
|
id.PosId = Sketcher::start;
|
||||||
|
@ -210,7 +210,7 @@ void SketcherValidation::on_findButton_clicked()
|
||||||
vertexIds.push_back(id);
|
vertexIds.push_back(id);
|
||||||
}
|
}
|
||||||
else if (g->getTypeId() == Part::GeomArcOfEllipse::getClassTypeId()) {
|
else if (g->getTypeId() == Part::GeomArcOfEllipse::getClassTypeId()) {
|
||||||
const Part::GeomArcOfEllipse *segm = dynamic_cast<const Part::GeomArcOfEllipse*>(g);
|
const Part::GeomArcOfEllipse *segm = static_cast<const Part::GeomArcOfEllipse*>(g);
|
||||||
VertexIds id;
|
VertexIds id;
|
||||||
id.GeoId = (int)i;
|
id.GeoId = (int)i;
|
||||||
id.PosId = Sketcher::start;
|
id.PosId = Sketcher::start;
|
||||||
|
@ -375,7 +375,7 @@ void SketcherValidation::on_findReversed_clicked()
|
||||||
Part::Geometry* g = geom[i];
|
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.
|
//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()) {
|
if (g->getTypeId() == Part::GeomArcOfCircle::getClassTypeId()) {
|
||||||
const Part::GeomArcOfCircle *segm = dynamic_cast<const Part::GeomArcOfCircle*>(g);
|
const Part::GeomArcOfCircle *segm = static_cast<const Part::GeomArcOfCircle*>(g);
|
||||||
if(segm->isReversedInXY()){
|
if(segm->isReversedInXY()){
|
||||||
points.push_back(segm->getStartPoint(/*emulateCCW=*/true));
|
points.push_back(segm->getStartPoint(/*emulateCCW=*/true));
|
||||||
points.push_back(segm->getEndPoint(/*emulateCCW=*/true));
|
points.push_back(segm->getEndPoint(/*emulateCCW=*/true));
|
||||||
|
|
|
@ -393,7 +393,6 @@ protected:
|
||||||
bool relative;
|
bool relative;
|
||||||
|
|
||||||
std::string oldWb;
|
std::string oldWb;
|
||||||
int antiAliasing;
|
|
||||||
|
|
||||||
Gui::Rubberband* rubberband;
|
Gui::Rubberband* rubberband;
|
||||||
App::Part* parentPart = nullptr;
|
App::Part* parentPart = nullptr;
|
||||||
|
|
|
@ -108,8 +108,6 @@ private:
|
||||||
out << "Server failed to listen at address " << addr << " and port " << port;
|
out << "Server failed to listen at address " << addr << " and port " << port;
|
||||||
throw Py::RuntimeError(out.str());
|
throw Py::RuntimeError(out.str());
|
||||||
}
|
}
|
||||||
|
|
||||||
return Py::None();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
Py::Object registerServerFirewall(const Py::Tuple& args)
|
Py::Object registerServerFirewall(const Py::Tuple& args)
|
||||||
|
|
Loading…
Reference in New Issue
Block a user