Robot: modernize C++11

* use nullptr
This commit is contained in:
wmayer
2022-03-23 19:06:14 +01:00
parent 58d1cc4818
commit a057e5486d
30 changed files with 75 additions and 75 deletions

View File

@@ -100,7 +100,7 @@ PyMOD_INIT_FUNC(Robot)
}
catch(const Base::Exception& e) {
PyErr_SetString(PyExc_ImportError, e.what());
PyMOD_Return(0);
PyMOD_Return(nullptr);
}
PyObject* robotModule = Robot::initModule();

View File

@@ -51,7 +51,7 @@ PROPERTY_SOURCE(Robot::Edge2TracObject, Robot::TrajectoryObject)
Edge2TracObject::Edge2TracObject()
{
ADD_PROPERTY_TYPE( Source, (0) , "Edge2Trac",Prop_None,"Edges to generate the Trajectory");
ADD_PROPERTY_TYPE( Source, (nullptr) , "Edge2Trac",Prop_None,"Edges to generate the Trajectory");
ADD_PROPERTY_TYPE( SegValue, (0.5), "Edge2Trac",Prop_None,"Max deviation from original geometry");
ADD_PROPERTY_TYPE( UseRotation, (0) , "Edge2Trac",Prop_None,"use orientation of the edge");
NbrOfEdges = 0;

View File

@@ -73,7 +73,7 @@ int Robot6AxisPy::PyInit(PyObject* /*args*/, PyObject* /*kwd*/)
PyObject* Robot6AxisPy::check(PyObject * /*args*/)
{
PyErr_SetString(PyExc_NotImplementedError, "Not yet implemented");
return 0;
return nullptr;
}
@@ -176,7 +176,7 @@ void Robot6AxisPy::setBase(Py::Object /*arg*/)
PyObject *Robot6AxisPy::getCustomAttributes(const char* /*attr*/) const
{
return 0;
return nullptr;
}
int Robot6AxisPy::setCustomAttributes(const char* /*attr*/, PyObject* /*obj*/)

View File

@@ -42,8 +42,8 @@ PROPERTY_SOURCE(Robot::RobotObject, App::GeoFeature)
RobotObject::RobotObject()
:block(false)
{
ADD_PROPERTY_TYPE(RobotVrmlFile ,(0),"Robot definition" ,Prop_None,"Included file with the VRML representation of the robot");
ADD_PROPERTY_TYPE(RobotKinematicFile,(0),"Robot definition",Prop_None,"Included file with kinematic definition of the robot Axis");
ADD_PROPERTY_TYPE(RobotVrmlFile ,(nullptr),"Robot definition" ,Prop_None,"Included file with the VRML representation of the robot");
ADD_PROPERTY_TYPE(RobotKinematicFile,(nullptr),"Robot definition",Prop_None,"Included file with kinematic definition of the robot Axis");
ADD_PROPERTY_TYPE(Axis1,(0.0),"Robot kinematic",Prop_None,"Axis 1 angle of the robot in degre");
ADD_PROPERTY_TYPE(Axis2,(0.0),"Robot kinematic",Prop_None,"Axis 2 angle of the robot in degre");
@@ -56,7 +56,7 @@ RobotObject::RobotObject()
ADD_PROPERTY_TYPE(Tcp,(Base::Placement()),"Robot kinematic",Prop_None,"Tcp of the robot");
ADD_PROPERTY_TYPE(Base,(Base::Placement()),"Robot kinematic",Prop_None,"Actual base frame of the robot");
ADD_PROPERTY_TYPE(Tool,(Base::Placement()),"Robot kinematic",Prop_None,"Tool frame of the robot (Tool)");
ADD_PROPERTY_TYPE(ToolShape,(0),"Robot definition",Prop_None,"Link to the Shape is used as Tool");
ADD_PROPERTY_TYPE(ToolShape,(nullptr),"Robot definition",Prop_None,"Link to the Shape is used as Tool");
ADD_PROPERTY_TYPE(ToolBase ,(Base::Placement()),"Robot definition",Prop_None,"Defines where to connect the ToolShape");
//ADD_PROPERTY_TYPE(Position,(Base::Placement()),"Robot definition",Prop_None,"Position of the robot in the simulation");
ADD_PROPERTY_TYPE(Home ,(0),"Robot kinematic",Prop_None,"Axis position for home");

View File

@@ -42,14 +42,14 @@ std::string RobotObjectPy::representation(void) const
PyObject* RobotObjectPy::getRobot(PyObject * /*args*/)
{
PyErr_SetString(PyExc_NotImplementedError, "Not yet implemented");
return 0;
return nullptr;
}
PyObject *RobotObjectPy::getCustomAttributes(const char* /*attr*/) const
{
return 0;
return nullptr;
}
int RobotObjectPy::setCustomAttributes(const char* /*attr*/, PyObject* /*obj*/)

View File

@@ -61,13 +61,13 @@ using namespace Base;
TYPESYSTEM_SOURCE(Robot::Trajectory , Base::Persistence)
Trajectory::Trajectory()
:pcTrajectory(0)
:pcTrajectory(nullptr)
{
}
Trajectory::Trajectory(const Trajectory& Trac)
:vpcWaypoints(Trac.vpcWaypoints.size()),pcTrajectory(0)
:vpcWaypoints(Trac.vpcWaypoints.size()),pcTrajectory(nullptr)
{
operator=(Trac);
}

View File

@@ -50,7 +50,7 @@ PROPERTY_SOURCE(Robot::TrajectoryCompound, Robot::TrajectoryObject)
TrajectoryCompound::TrajectoryCompound()
{
ADD_PROPERTY_TYPE( Source, (0) , "Compound",Prop_None,"list of trajectories to combine");
ADD_PROPERTY_TYPE( Source, (nullptr) , "Compound",Prop_None,"list of trajectories to combine");
}

View File

@@ -46,13 +46,13 @@ using namespace App;
PROPERTY_SOURCE(Robot::TrajectoryDressUpObject, Robot::TrajectoryObject)
const char* TrajectoryDressUpObject::ContTypeEnums[]= {"DontChange","Continues","Discontinues",NULL};
const char* TrajectoryDressUpObject::AddTypeEnums[] = {"DontChange","UseOrientation","AddPosition","AddOrintation","AddPositionAndOrientation",NULL};
const char* TrajectoryDressUpObject::ContTypeEnums[]= {"DontChange","Continues","Discontinues",nullptr};
const char* TrajectoryDressUpObject::AddTypeEnums[] = {"DontChange","UseOrientation","AddPosition","AddOrintation","AddPositionAndOrientation",nullptr};
TrajectoryDressUpObject::TrajectoryDressUpObject()
{
ADD_PROPERTY_TYPE( Source, (0) , "TrajectoryDressUp",Prop_None,"Trajectory to dress up");
ADD_PROPERTY_TYPE( Source, (nullptr) , "TrajectoryDressUp",Prop_None,"Trajectory to dress up");
ADD_PROPERTY_TYPE( Speed, (1000) , "TrajectoryDressUp",Prop_None,"Speed to use");
ADD_PROPERTY_TYPE( UseSpeed , (0) , "TrajectoryDressUp",Prop_None,"Switch the speed usage on");
ADD_PROPERTY_TYPE( Acceleration, (1000) , "TrajectoryDressUp",Prop_None,"Acceleration to use");

View File

@@ -57,7 +57,7 @@ PyObject *TrajectoryPy::PyMake(struct _typeobject *, PyObject *, PyObject *) //
// constructor method
int TrajectoryPy::PyInit(PyObject* args, PyObject* /*kwd*/)
{
PyObject *pcObj=0;
PyObject *pcObj=nullptr;
if (!PyArg_ParseTuple(args, "|O!", &(PyList_Type), &pcObj))
return -1;
@@ -119,7 +119,7 @@ PyObject* TrajectoryPy::position(PyObject * args)
{
double pos;
if (!PyArg_ParseTuple(args, "d", &pos))
return NULL;
return nullptr;
return (new Base::PlacementPy(new Base::Placement(getTrajectoryPtr()->getPosition(pos))));
}
@@ -128,7 +128,7 @@ PyObject* TrajectoryPy::velocity(PyObject * args)
{
double pos;
if (!PyArg_ParseTuple(args, "d", &pos))
return NULL;
return nullptr;
// return velocity as float
return Py::new_reference_to(Py::Float(getTrajectoryPtr()->getVelocity(pos)));
@@ -138,7 +138,7 @@ PyObject* TrajectoryPy::deleteLast(PyObject *args)
{
int n=1;
if (!PyArg_ParseTuple(args, "|i", &n))
return NULL;
return nullptr;
getTrajectoryPtr()->deleteLast(n);
return new TrajectoryPy(new Robot::Trajectory(*getTrajectoryPtr()));
}
@@ -173,7 +173,7 @@ void TrajectoryPy::setWaypoints(Py::List)
PyObject *TrajectoryPy::getCustomAttributes(const char* /*attr*/) const
{
return 0;
return nullptr;
}
int TrajectoryPy::setCustomAttributes(const char* /*attr*/, PyObject* /*obj*/)

View File

@@ -86,13 +86,13 @@ int WaypointPy::PyInit(PyObject* args, PyObject* kwd)
PyObject* pos;
char* name = "P";
char* type = "PTP";
PyObject* vel = 0;
PyObject* acc = 0;
PyObject* vel = nullptr;
PyObject* acc = nullptr;
int cont = 0;
int tool = 0;
int base = 0;
static char* kwlist[] = { "Pos", "type","name", "vel", "cont", "tool", "base", "acc" ,NULL };
static char* kwlist[] = { "Pos", "type","name", "vel", "cont", "tool", "base", "acc" ,nullptr };
if (!PyArg_ParseTupleAndKeywords(args, kwd, "O!|ssOiiiO", kwlist,
&(Base::PlacementPy::Type), &pos, // the placement object
@@ -114,7 +114,7 @@ int WaypointPy::PyInit(PyObject* args, PyObject* kwd)
else
getWaypointPtr()->Type = Waypoint::UNDEF;
if (vel == 0)
if (vel == nullptr)
switch (getWaypointPtr()->Type) {
case Waypoint::PTP:
getWaypointPtr()->Velocity = 100;
@@ -133,7 +133,7 @@ int WaypointPy::PyInit(PyObject* args, PyObject* kwd)
getWaypointPtr()->Cont = cont ? true : false;
getWaypointPtr()->Tool = tool;
getWaypointPtr()->Base = base;
if (acc == 0)
if (acc == nullptr)
getWaypointPtr()->Acceleration = 100;
else
getWaypointPtr()->Acceleration = Base::UnitsApi::toDouble(acc, Base::Unit::Acceleration);
@@ -248,7 +248,7 @@ void WaypointPy::setBase(Py::Long arg)
PyObject *WaypointPy::getCustomAttributes(const char* /*attr*/) const
{
return 0;
return nullptr;
}
int WaypointPy::setCustomAttributes(const char* /*attr*/, PyObject* /*obj*/)

View File

@@ -161,7 +161,7 @@ Path* Path::Read(istream& is) {
} else {
throw Error_MotionIO_Unexpected_Traj();
}
return NULL; // just to avoid the warning;
return nullptr; // just to avoid the warning;
}

View File

@@ -68,18 +68,18 @@ RotationalInterpolation* RotationalInterpolation::Read(istream& is) {
EatEnd(is,']');
IOTracePop();
IOTracePop();
return NULL;
return nullptr;
} else if (strcmp(storage,"TWOAXIS")==0) {
IOTrace("TWOAXIS");
throw Error_Not_Implemented();
EatEnd(is,']');
IOTracePop();
IOTracePop();
return NULL;
return nullptr;
} else {
throw Error_MotionIO_Unexpected_Traj();
}
return NULL; // just to avoid the warning;
return nullptr; // just to avoid the warning;
}
}

View File

@@ -71,7 +71,7 @@ Trajectory* Trajectory::Read(std::istream& is) {
} else {
throw Error_MotionIO_Unexpected_Traj();
}
return NULL; // just to avoid the warning;
return nullptr; // just to avoid the warning;
}

View File

@@ -139,7 +139,7 @@ namespace KDL {
VelocityProfile* Trajectory_Composite::GetProfile()
{
return 0;
return nullptr;
}
}

View File

@@ -37,7 +37,7 @@ namespace KDL {
}
}
// Eats until the end of the line
int _EatUntilEndOfLine( std::istream& is, int* countp=NULL) {
int _EatUntilEndOfLine( std::istream& is, int* countp=nullptr) {
int ch;
int count;
count = 0;
@@ -46,12 +46,12 @@ namespace KDL {
count++;
_check_istream(is);
} while (ch!='\n');
if (countp!=NULL) *countp = count;
if (countp!=nullptr) *countp = count;
return ch;
}
// Eats until the end of the comment
int _EatUntilEndOfComment( std::istream& is, int* countp=NULL) {
int _EatUntilEndOfComment( std::istream& is, int* countp=nullptr) {
int ch;
int count;
count = 0;
@@ -66,14 +66,14 @@ namespace KDL {
break;
}
} while (true);
if (countp!=NULL) *countp = count;
if (countp!=nullptr) *countp = count;
ch = is.get();
return ch;
}
// Eats space-like characters and comments
// possibly returns the number of space-like characters eaten.
int _EatSpace( std::istream& is,int* countp=NULL) {
int _EatSpace( std::istream& is,int* countp=nullptr) {
int ch;
int count;
count=-1;
@@ -97,7 +97,7 @@ int _EatSpace( std::istream& is,int* countp=NULL) {
}
}
} while ((ch==' ')||(ch=='\n')||(ch=='\t'));
if (countp!=NULL) *countp = count;
if (countp!=nullptr) *countp = count;
return ch;
}
@@ -189,7 +189,7 @@ void EatWord(std::istream& is,const char* delim,char* storage,int maxsize)
p = storage;
size=0;
int count = 0;
while ((count==0)&&(strchr(delim,ch)==NULL)) {
while ((count==0)&&(strchr(delim,ch)==nullptr)) {
*p = (char) toupper(ch);
++p;
if (size==maxsize) {

View File

@@ -92,7 +92,7 @@ VelocityProfile* VelocityProfile::Read(istream& is) {
else {
throw Error_MotionIO_Unexpected_MotProf();
}
return 0;
return nullptr;
}

View File

@@ -78,7 +78,7 @@ PyMOD_INIT_FUNC(RobotGui)
{
if (!Gui::Application::Instance) {
PyErr_SetString(PyExc_ImportError, "Cannot load Gui module in console application.");
PyMOD_Return(0);
PyMOD_Return(nullptr);
}
try {
Base::Interpreter().runString("import PartGui");
@@ -98,7 +98,7 @@ PyMOD_INIT_FUNC(RobotGui)
}
catch(const Base::Exception& e) {
PyErr_SetString(PyExc_ImportError, e.what());
PyMOD_Return(0);
PyMOD_Return(nullptr);
}
PyObject* mod = RobotGui::initModule();
Base::Console().Log("Loading GUI of Robot module... done\n");

View File

@@ -70,14 +70,14 @@ void CmdRobotExportKukaCompact::activated(int)
std::vector<Gui::SelectionSingleton::SelObj> Sel = getSelection().getSelection();
Robot::RobotObject *pcRobotObject=0;
Robot::RobotObject *pcRobotObject=nullptr;
if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[0].pObject);
else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[1].pObject);
std::string RoboName = pcRobotObject->getNameInDocument();
Robot::TrajectoryObject *pcTrajectoryObject=0;
Robot::TrajectoryObject *pcTrajectoryObject=nullptr;
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
pcTrajectoryObject = static_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
@@ -132,14 +132,14 @@ void CmdRobotExportKukaFull::activated(int)
std::vector<Gui::SelectionSingleton::SelObj> Sel = getSelection().getSelection();
Robot::RobotObject *pcRobotObject=0;
Robot::RobotObject *pcRobotObject=nullptr;
if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[0].pObject);
else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[1].pObject);
//std::string RoboName = pcRobotObject->getNameInDocument();
Robot::TrajectoryObject *pcTrajectoryObject=0;
Robot::TrajectoryObject *pcTrajectoryObject=nullptr;
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
pcTrajectoryObject = static_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())

View File

@@ -115,14 +115,14 @@ void CmdRobotInsertWaypoint::activated(int)
std::vector<Gui::SelectionSingleton::SelObj> Sel = getSelection().getSelection();
Robot::RobotObject *pcRobotObject=0;
Robot::RobotObject *pcRobotObject=nullptr;
if(Sel[0].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[0].pObject);
else if(Sel[1].pObject->getTypeId() == Robot::RobotObject::getClassTypeId())
pcRobotObject = static_cast<Robot::RobotObject*>(Sel[1].pObject);
std::string RoboName = pcRobotObject->getNameInDocument();
Robot::TrajectoryObject *pcTrajectoryObject=0;
Robot::TrajectoryObject *pcTrajectoryObject=nullptr;
if(Sel[0].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
pcTrajectoryObject = static_cast<Robot::TrajectoryObject*>(Sel[0].pObject);
else if(Sel[1].pObject->getTypeId() == Robot::TrajectoryObject::getClassTypeId())
@@ -187,7 +187,7 @@ void CmdRobotInsertWaypointPreselect::activated(int)
}
std::string TrakName = pcTrajectoryObject->getNameInDocument();
if(PreSel.pDocName == 0){
if(PreSel.pDocName == nullptr){
QMessageBox::warning(Gui::getMainWindow(), QObject::tr("No preselection"),
QObject::tr("You have to hover above a geometry (Preselection) with the mouse to use this command. See documentation for details."));
return;
@@ -218,7 +218,7 @@ CmdRobotSetDefaultOrientation::CmdRobotSetDefaultOrientation()
sToolTipText = QT_TR_NOOP("Set the default orientation for subsequent commands for waypoint creation");
sWhatsThis = "Robot_SetDefaultOrientation";
sStatusTip = sToolTipText;
sPixmap = 0;
sPixmap = nullptr;
}
@@ -256,7 +256,7 @@ CmdRobotSetDefaultValues::CmdRobotSetDefaultValues()
sToolTipText = QT_TR_NOOP("Set the default values for speed, acceleration and continuity for subsequent commands of waypoint creation");
sWhatsThis = "Robot_SetDefaultValues";
sStatusTip = sToolTipText;
sPixmap = 0;
sPixmap = nullptr;
}
@@ -265,7 +265,7 @@ void CmdRobotSetDefaultValues::activated(int)
{
bool ok;
QString text = QInputDialog::getText(0, QObject::tr("Set default speed"),
QString text = QInputDialog::getText(nullptr, QObject::tr("Set default speed"),
QObject::tr("speed: (e.g. 1 m/s or 3 cm/s)"), QLineEdit::Normal,
QString::fromLatin1("1 m/s"), &ok, Qt::MSWindowsFixedSizeDialogHint);
if ( ok && !text.isEmpty() ) {
@@ -275,14 +275,14 @@ void CmdRobotSetDefaultValues::activated(int)
QStringList items;
items << QString::fromLatin1("False") << QString::fromLatin1("True");
QString item = QInputDialog::getItem(0, QObject::tr("Set default continuity"),
QString item = QInputDialog::getItem(nullptr, QObject::tr("Set default continuity"),
QObject::tr("continuous ?"), items, 0, false, &ok, Qt::MSWindowsFixedSizeDialogHint);
if (ok && !item.isEmpty())
doCommand(Doc,"_DefCont = %s",item.toLatin1().constData());
text.clear();
text = QInputDialog::getText(0, QObject::tr("Set default acceleration"),
text = QInputDialog::getText(nullptr, QObject::tr("Set default acceleration"),
QObject::tr("acceleration: (e.g. 1 m/s^2 or 3 cm/s^2)"), QLineEdit::Normal,
QString::fromLatin1("1 m/s^2"), &ok, Qt::MSWindowsFixedSizeDialogHint);
if ( ok && !text.isEmpty() ) {

View File

@@ -48,7 +48,7 @@ TaskEdge2TracParameter::TaskEdge2TracParameter(Robot::Edge2TracObject *pcObject,
true,
parent),
pcObject(pcObject),
HideShowObj(0)
HideShowObj(nullptr)
{
// we need a separate container widget to add all controls to
proxy = new QWidget(this);

View File

@@ -50,7 +50,7 @@ class TaskEdge2TracParameter : public Gui::TaskView::TaskBox
Q_OBJECT
public:
TaskEdge2TracParameter(Robot::Edge2TracObject *pcObject,QWidget *parent = 0);
TaskEdge2TracParameter(Robot::Edge2TracObject *pcObject,QWidget *parent = nullptr);
~TaskEdge2TracParameter();
void setEdgeAndClusterNbr(int NbrEdges,int NbrClusters);

View File

@@ -51,7 +51,7 @@ class TaskRobot6Axis : public Gui::TaskView::TaskBox
Q_OBJECT
public:
TaskRobot6Axis(Robot::RobotObject *pcRobotObject,QWidget *parent = 0);
TaskRobot6Axis(Robot::RobotObject *pcRobotObject,QWidget *parent = nullptr);
~TaskRobot6Axis();
void setRobot(Robot::RobotObject *pcRobotObject);

View File

@@ -50,7 +50,7 @@ class TaskRobotControl : public Gui::TaskView::TaskBox
Q_OBJECT
public:
TaskRobotControl(Robot::RobotObject *pcRobotObject,QWidget *parent = 0);
TaskRobotControl(Robot::RobotObject *pcRobotObject,QWidget *parent = nullptr);
~TaskRobotControl();
void setRobot(Robot::RobotObject *pcRobotObject);

View File

@@ -50,7 +50,7 @@ class TaskRobotMessages : public Gui::TaskView::TaskBox
Q_OBJECT
public:
TaskRobotMessages(Robot::RobotObject *pcRobotObject,QWidget *parent = 0);
TaskRobotMessages(Robot::RobotObject *pcRobotObject,QWidget *parent = nullptr);
~TaskRobotMessages();
private Q_SLOTS:

View File

@@ -58,7 +58,7 @@ class TaskTrajectory : public Gui::TaskView::TaskBox
Q_OBJECT
public:
TaskTrajectory(Robot::RobotObject *pcRobotObject,Robot::TrajectoryObject *pcTrajectoryObject,QWidget *parent = 0);
TaskTrajectory(Robot::RobotObject *pcRobotObject,Robot::TrajectoryObject *pcTrajectoryObject,QWidget *parent = nullptr);
~TaskTrajectory();
/// Observer message from the Selection
void OnChange(Gui::SelectionSingleton::SubjectType &rCaller,

View File

@@ -44,7 +44,7 @@ class TaskTrajectoryDressUpParameter : public Gui::TaskView::TaskBox
Q_OBJECT
public:
TaskTrajectoryDressUpParameter(Robot::TrajectoryDressUpObject *obj,QWidget *parent = 0);
TaskTrajectoryDressUpParameter(Robot::TrajectoryDressUpObject *obj,QWidget *parent = nullptr);
~TaskTrajectoryDressUpParameter();
/// this methode write the values from the Gui to the object, usually in accept()

View File

@@ -44,8 +44,8 @@ using namespace RobotGui;
TaskWatcherRobot::TaskWatcherRobot()
: Gui::TaskView::TaskWatcher("SELECT Robot::RobotObject COUNT 1")
{
rob = new TaskRobot6Axis(0);
ctr = new TaskRobotControl(0);
rob = new TaskRobot6Axis(nullptr);
ctr = new TaskRobotControl(nullptr);
Content.push_back(rob);
Content.push_back(ctr);

View File

@@ -46,7 +46,7 @@ class TrajectorySimulate : public QDialog
Q_OBJECT
public:
TrajectorySimulate(Robot::RobotObject *pcRobotObject,Robot::TrajectoryObject *pcTrajectoryObject,QWidget *parent = 0);
TrajectorySimulate(Robot::RobotObject *pcRobotObject,Robot::TrajectoryObject *pcTrajectoryObject,QWidget *parent = nullptr);
~TrajectorySimulate();
private Q_SLOTS:

View File

@@ -56,7 +56,7 @@ using namespace RobotGui;
PROPERTY_SOURCE(RobotGui::ViewProviderRobotObject, Gui::ViewProviderGeometryObject)
ViewProviderRobotObject::ViewProviderRobotObject()
: pcDragger(0),toolShape(0)
: pcDragger(nullptr),toolShape(nullptr)
{
ADD_PROPERTY(Manipulator,(0));
@@ -79,7 +79,7 @@ ViewProviderRobotObject::ViewProviderRobotObject()
pcTcpRoot->ref();
Axis1Node = Axis2Node = Axis3Node = Axis4Node = Axis5Node = Axis6Node = 0;
Axis1Node = Axis2Node = Axis3Node = Axis4Node = Axis5Node = Axis6Node = nullptr;
}
ViewProviderRobotObject::~ViewProviderRobotObject()
@@ -92,7 +92,7 @@ ViewProviderRobotObject::~ViewProviderRobotObject()
void ViewProviderRobotObject::setDragger()
{
assert(pcDragger==0);
assert(pcDragger==nullptr);
pcDragger = new SoJackDragger();
pcDragger->addMotionCallback(sDraggerMotionCallback,this);
pcTcpRoot->addChild(pcDragger);
@@ -112,7 +112,7 @@ void ViewProviderRobotObject::resetDragger()
{
assert(pcDragger);
Gui::coinRemoveAllChildren(pcTcpRoot);
pcDragger = 0;
pcDragger = nullptr;
}
void ViewProviderRobotObject::attach(App::DocumentObject *pcObj)
@@ -190,7 +190,7 @@ void ViewProviderRobotObject::updateData(const App::Property* prop)
pcRobotRoot->addChild(pcTcpRoot);
}
// search for the connection points +++++++++++++++++++++++++++++++++++++++++++++++++
Axis1Node = Axis2Node = Axis3Node = Axis4Node = Axis5Node = Axis6Node = 0;
Axis1Node = Axis2Node = Axis3Node = Axis4Node = Axis5Node = Axis6Node = nullptr;
SoSearchAction searchAction;
SoPath * path;
@@ -329,7 +329,7 @@ void ViewProviderRobotObject::updateData(const App::Property* prop)
toolShape = Gui::Application::Instance->getViewProvider(o);
toolShape->setTransformation((robObj->Tcp.getValue() * (robObj->ToolBase.getValue().inverse())).toMatrix());
}else
toolShape = 0;
toolShape = nullptr;
}
}

View File

@@ -92,28 +92,28 @@ void Workbench::activated()
const char* RobotAndTrac[] = {
"Robot_InsertWaypoint",
"Robot_InsertWaypointPreselect",
0};
nullptr};
const char* Robot[] = {
"Robot_AddToolShape",
"Robot_SetHomePos",
"Robot_RestoreHomePos",
0};
nullptr};
const char* Empty[] = {
"Robot_InsertKukaIR500",
"Robot_InsertKukaIR16",
"Robot_InsertKukaIR210",
"Robot_InsertKukaIR125",
0};
nullptr};
const char* TracSingle[] = {
"Robot_TrajectoryDressUp",
0};
nullptr};
const char* TracMore[] = {
"Robot_TrajectoryCompound",
0};
nullptr};
std::vector<Gui::TaskView::TaskWatcher*> Watcher;