diff --git a/GraspPlanning/ApproachMovementSurfaceNormal.cpp b/GraspPlanning/ApproachMovementSurfaceNormal.cpp index e344e92f105579c629eb99b1785c83a9b406a0ff..8ecdaf7033ab110693afcb7a4cf85c155605cac4 100644 --- a/GraspPlanning/ApproachMovementSurfaceNormal.cpp +++ b/GraspPlanning/ApproachMovementSurfaceNormal.cpp @@ -85,7 +85,7 @@ namespace GraspStudio if (!getPositionOnObject(position, approachDir)) { - GRASPSTUDIO_ERROR << "no position on object?!" << endl; + GRASPSTUDIO_ERROR << "no position on object?!" << std::endl; return pose; } @@ -158,7 +158,7 @@ namespace GraspStudio if (loop > 1000) { - VR_ERROR << "INTERNAL ERROR, aborting..." << endl; + VR_ERROR << "INTERNAL ERROR, aborting..." << std::endl; return false; } diff --git a/GraspPlanning/ContactConeGenerator.cpp b/GraspPlanning/ContactConeGenerator.cpp index 31e84c326e25bd7b9b8a7c12a2a7d2ed3ac0b579..f002552dd72895ab8392f8e7fce8dedd78a7bdec 100644 --- a/GraspPlanning/ContactConeGenerator.cpp +++ b/GraspPlanning/ContactConeGenerator.cpp @@ -57,14 +57,14 @@ namespace GraspStudio if (printInfo) { - cout << "Compute Cone Points" << endl; - cout << "Point.p:" << endl; - cout << point.p << endl; - cout << "Point.n:" << endl; - cout << point.n << endl; - cout << "Point.force:" << endl; - cout << point.force << endl; - cout << "storeConePoints.size():" << storeConePoints.size() << endl; + std::cout << "Compute Cone Points" << std::endl; + std::cout << "Point.p:" << std::endl; + std::cout << point.p << std::endl; + std::cout << "Point.n:" << std::endl; + std::cout << point.n << std::endl; + std::cout << "Point.force:" << std::endl; + std::cout << point.force << std::endl; + std::cout << "storeConePoints.size():" << storeConePoints.size() << std::endl; } //Rotate generic friction cone to align with object normals @@ -78,7 +78,7 @@ namespace GraspStudio if (printInfo) { - cout << "frictionConeSamples:" << frictionConeSamples << endl; + std::cout << "frictionConeSamples:" << frictionConeSamples << std::endl; } for (int i = 0; i < frictionConeSamples; i++) @@ -93,13 +93,13 @@ namespace GraspStudio if (printInfo) { - cout << "Loop " << i << endl; - cout << "newConePoint.p:" << endl; - cout << newConePoint.p << endl; - cout << "newConePoint.n:" << endl; - cout << newConePoint.n << endl; - cout << "newConePoint.force:" << endl; - cout << newConePoint.force << endl; + std::cout << "Loop " << i << std::endl; + std::cout << "newConePoint.p:" << std::endl; + std::cout << newConePoint.p << std::endl; + std::cout << "newConePoint.n:" << std::endl; + std::cout << newConePoint.n << std::endl; + std::cout << "newConePoint.force:" << std::endl; + std::cout << newConePoint.force << std::endl; } storeConePoints.push_back(newConePoint); @@ -112,14 +112,14 @@ namespace GraspStudio if (printInfo) { - cout << "Compute Cone Points" << endl; - cout << "Point.p:" << endl; - cout << point.p << endl; - cout << "Point.n:" << endl; - cout << point.n << endl; - cout << "Point.force:" << endl; - cout << point.force << endl; - cout << "storeConePoints.size():" << storeConePoints.size() << endl; + std::cout << "Compute Cone Points" << std::endl; + std::cout << "Point.p:" << std::endl; + std::cout << point.p << std::endl; + std::cout << "Point.n:" << std::endl; + std::cout << point.n << std::endl; + std::cout << "Point.force:" << std::endl; + std::cout << point.force << std::endl; + std::cout << "storeConePoints.size():" << storeConePoints.size() << std::endl; } //Rotate generic friction cone to align with object normals @@ -133,7 +133,7 @@ namespace GraspStudio if (printInfo) { - cout << "frictionConeSamples:" << frictionConeSamples << endl; + std::cout << "frictionConeSamples:" << frictionConeSamples << std::endl; } for (int i = 0; i < frictionConeSamples; i++) @@ -145,9 +145,9 @@ namespace GraspStudio if (printInfo) { - cout << "Loop " << i << endl; - cout << "newConePoint:" << endl; - cout << newConePoint << endl; + std::cout << "Loop " << i << std::endl; + std::cout << "newConePoint:" << std::endl; + std::cout << newConePoint << std::endl; } storeConePoints.push_back(newConePoint); diff --git a/GraspPlanning/ConvexHullGenerator.cpp b/GraspPlanning/ConvexHullGenerator.cpp index 6d0cb7f57a11cc4ee7ef0333f53ab809e59fe8e3..e41589e13bb1bad67c1eb5a23526c25dffb614fc 100644 --- a/GraspPlanning/ConvexHullGenerator.cpp +++ b/GraspPlanning/ConvexHullGenerator.cpp @@ -220,7 +220,7 @@ namespace GraspStudio ConvexHull3D projectedHull; if (!CreateConvexHull(vProjectedPoints, projectedHull, false)) { - cout << __FUNCTION__ << " Could not create hull of projected points, aborting..." << endl; + std::cout << __FUNCTION__ << " Could not create hull of projected points, aborting..." << std::endl; return false; } bool bRes = CreateIVModel(projectedHull, pStoreResult, false); @@ -340,15 +340,15 @@ namespace GraspStudio { for (std::size_t i = 0; i < pointsInput.size(); i++) { - cout << "v" << i << ": " << pointsInput[i].p[0] << "," << pointsInput[i].p[1] << "," << pointsInput[i].p[2] << "," - << pointsInput[i].n[0] << "," << pointsInput[i].n[1] << "," << pointsInput[i].n[2] << endl; + std::cout << "v" << i << ": " << pointsInput[i].p[0] << "," << pointsInput[i].p[1] << "," << pointsInput[i].p[2] << "," + << pointsInput[i].n[0] << "," << pointsInput[i].n[1] << "," << pointsInput[i].n[2] << std::endl; } } void ConvexHullGenerator::PrintStatistics(VirtualRobot::MathTools::ConvexHull6DPtr convHull) { if (!convHull) { - GRASPSTUDIO_ERROR << " Null data to print" << endl; + GRASPSTUDIO_ERROR << " Null data to print" << std::endl; return; } @@ -424,13 +424,13 @@ namespace GraspStudio } } - cout << "Conv Hull Bounds:" << endl; - cout << "\t\t x : " << minValue[0] << "," << maxValue[0] << endl; - cout << "\t\t y : " << minValue[1] << "," << maxValue[1] << endl; - cout << "\t\t z : " << minValue[2] << "," << maxValue[2] << endl; - cout << "\t\t nx: " << minValue[3] << "," << maxValue[3] << endl; - cout << "\t\t ny: " << minValue[4] << "," << maxValue[4] << endl; - cout << "\t\t nz: " << minValue[5] << "," << maxValue[5] << endl; + std::cout << "Conv Hull Bounds:" << std::endl; + std::cout << "\t\t x : " << minValue[0] << "," << maxValue[0] << std::endl; + std::cout << "\t\t y : " << minValue[1] << "," << maxValue[1] << std::endl; + std::cout << "\t\t z : " << minValue[2] << "," << maxValue[2] << std::endl; + std::cout << "\t\t nx: " << minValue[3] << "," << maxValue[3] << std::endl; + std::cout << "\t\t ny: " << minValue[4] << "," << maxValue[4] << std::endl; + std::cout << "\t\t nz: " << minValue[5] << "," << maxValue[5] << std::endl; } bool ConvexHullGenerator::checkVerticeOrientation(const Eigen::Vector3f& v1, const Eigen::Vector3f& v2, const Eigen::Vector3f& v3, const Eigen::Vector3f& n) diff --git a/GraspPlanning/ConvexHullGeneratorQhull.cpp b/GraspPlanning/ConvexHullGeneratorQhull.cpp index 1d529943bb0fea1da9d0646d1cf98b2fd0ed9c2b..e9d6759296ead616259c18a07d410ae550e9f92c 100644 --- a/GraspPlanning/ConvexHullGeneratorQhull.cpp +++ b/GraspPlanning/ConvexHullGeneratorQhull.cpp @@ -38305,7 +38305,7 @@ VirtualRobot::MathTools::ConvexHull3DPtr ConvexHullGenerator::CreateConvexHull(c if (nPoints < 4) { - cout << __FUNCTION__ << "Error: Need at least 4 points (nr of points registered: " << nPoints << ")" << endl; + std::cout << __FUNCTION__ << "Error: Need at least 4 points (nr of points registered: " << nPoints << ")" << std::endl; return result; } @@ -38339,7 +38339,7 @@ VirtualRobot::MathTools::ConvexHull3DPtr ConvexHullGenerator::CreateConvexHull(c sprintf(flags, "qhull s Qt FA Pp"); // QJ is faster than Qt (but the results seem to be less accurate, see www.qhull.org documentation) #endif - //cout << "QHULL input: nVertices: " << pointsInput.size() << endl; + //cout << "QHULL input: nVertices: " << pointsInput.size() << std::endl; ConvertPoints(pointsInput, points); /*for (i=numpoints; i--; ) rows[i]= points+dim*i; @@ -38360,19 +38360,19 @@ VirtualRobot::MathTools::ConvexHull3DPtr ConvexHullGenerator::CreateConvexHull(c //int convexNumFaces2 = qh num_facets; /*int convexNumVert2 =*/ simox_QHqh_setsize(qh, simox_QHqh_facetvertices(qh, facet_list, nullptr, false)); /* - cout << "Numfacets1:" << convexNumFaces << endl; - cout << "Numvertices1:" << convexNumVert << endl; - cout << "Numfacets2:" << convexNumFaces2 << endl; - cout << "Numvertices2:" << convexNumVert2 << endl;*/ + std::cout << "Numfacets1:" << convexNumFaces << std::endl; + std::cout << "Numvertices1:" << convexNumVert << std::endl; + std::cout << "Numfacets2:" << convexNumFaces2 << std::endl; + std::cout << "Numvertices2:" << convexNumVert2 << std::endl;*/ /* 'qht->facet_list' contains the convex hull */ Eigen::Vector3f v[3]; int nIds[3]; TriangleFace f; int nFacets = 0; - //cout << "Volume: " << qht-> totvol << endl; + //cout << "Volume: " << qht-> totvol << std::endl; simox_QHqh_getarea(qh, qh->facet_list); - //cout << "Volume: " << qht-> totvol << endl; + //cout << "Volume: " << qht-> totvol << std::endl; result->volume = qh-> totvol; @@ -38412,13 +38412,13 @@ VirtualRobot::MathTools::ConvexHull3DPtr ConvexHullGenerator::CreateConvexHull(c int c = 0; #ifdef CONVEXHULL_DEBUG_OUTPUT - cout << "FACET " << nFacets << ":" << endl; + std::cout << "FACET " << nFacets << ":" << std::endl; #endif FOREACHvertex_(facet->vertices) { #ifdef CONVEXHULL_DEBUG_OUTPUT - cout << vertex->point[0] << "," << vertex->point[1] << "," << vertex->point[2] << endl; + std::cout << vertex->point[0] << "," << vertex->point[1] << "," << vertex->point[2] << std::endl; #endif if (c < 3) @@ -38432,7 +38432,7 @@ VirtualRobot::MathTools::ConvexHull3DPtr ConvexHullGenerator::CreateConvexHull(c } else { - cout << __FUNCTION__ << ": Error, facet with more than 3 vertices not supported ... face nr:" << nFacets << endl; + std::cout << __FUNCTION__ << ": Error, facet with more than 3 vertices not supported ... face nr:" << nFacets << std::endl; } } f.id1 = nIds[0]; @@ -38441,7 +38441,7 @@ VirtualRobot::MathTools::ConvexHull3DPtr ConvexHullGenerator::CreateConvexHull(c f.normal[0] = facet->normal[0]; f.normal[1] = facet->normal[1]; f.normal[2] = facet->normal[2]; - //cout << "Normal: " << f.m_Normal.x << "," << f.m_Normal.y << "," << f.m_Normal.z << endl; + //cout << "Normal: " << f.m_Normal.x << "," << f.m_Normal.y << "," << f.m_Normal.z << std::endl; double dist = simox_QHqh_distnorm(3, pCenter, facet->normal, &(facet->offset)); @@ -38456,8 +38456,8 @@ VirtualRobot::MathTools::ConvexHull3DPtr ConvexHullGenerator::CreateConvexHull(c } result->maxDistFacetCenter = maxDist; /* - cout << "QHULL result: nVertices: " << storeResult.vertices.size() << endl; - cout << "QHULL result: nFactes: " << nFacets << endl; + std::cout << "QHULL result: nVertices: " << storeResult.vertices.size() << std::endl; + std::cout << "QHULL result: nFactes: " << nFacets << std::endl; */ } @@ -38472,7 +38472,7 @@ VirtualRobot::MathTools::ConvexHull3DPtr ConvexHullGenerator::CreateConvexHull(c //clock_t endT = clock(); //long timeMS = (long)(((float)(endT - startT) / (float)CLOCKS_PER_SEC) * 1000.0); - //cout << __FUNCTION__ << ": Created convex hull in " << timeMS << " ms" << endl; + //cout << __FUNCTION__ << ": Created convex hull in " << timeMS << " ms" << std::endl; return result; } @@ -38486,7 +38486,7 @@ VirtualRobot::MathTools::ConvexHull6DPtr ConvexHullGenerator::CreateConvexHull(s if (nPoints < 4) { - cout << __FUNCTION__ << "Error: Need at least 4 points (nr of points registered: " << nPoints << ")" << endl; + std::cout << __FUNCTION__ << "Error: Need at least 4 points (nr of points registered: " << nPoints << ")" << std::endl; return result; @@ -38525,7 +38525,7 @@ VirtualRobot::MathTools::ConvexHull6DPtr ConvexHullGenerator::CreateConvexHull(s sprintf(flags, "qhull QJ FA Pp"); // QJ is faster than Qt (but the results seem to be less accurate, see www.qhull.org documentation) #endif - //cout << "QHULL input: nVertices: " << pointsInput.size() << endl; + //cout << "QHULL input: nVertices: " << pointsInput.size() << std::endl; //printVertices(pointsInput); ConvertPoints(pointsInput, points); simox_QHqhT simox_QHqh_qh; /* Qhull's data structure. First argument of most calls */ @@ -38605,8 +38605,8 @@ VirtualRobot::MathTools::ConvexHull6DPtr ConvexHullGenerator::CreateConvexHull(s if (printInfo) { - cout << "FACET " << nFacets << ":" << endl; - cout << "Offset:" << facet->offset << endl; + std::cout << "FACET " << nFacets << ":" << std::endl; + std::cout << "Offset:" << facet->offset << std::endl; } #endif @@ -38617,7 +38617,7 @@ VirtualRobot::MathTools::ConvexHull6DPtr ConvexHullGenerator::CreateConvexHull(s if (printInfo) { - cout << vertex->point[0] << "," << vertex->point[1] << "," << vertex->point[2] << "," << vertex->point[3] << "," << vertex->point[4] << "," << vertex->point[5] << endl; + std::cout << vertex->point[0] << "," << vertex->point[1] << "," << vertex->point[2] << "," << vertex->point[3] << "," << vertex->point[4] << "," << vertex->point[5] << std::endl; } #endif @@ -38636,7 +38636,7 @@ VirtualRobot::MathTools::ConvexHull6DPtr ConvexHullGenerator::CreateConvexHull(s } else { - cout << __FUNCTION__ << ": Error, facet with more than 6 vertices not supported ... face nr:" << nFacets << endl; + std::cout << __FUNCTION__ << ": Error, facet with more than 6 vertices not supported ... face nr:" << nFacets << std::endl; } } f.id[0] = nIds[0]; @@ -38667,21 +38667,21 @@ VirtualRobot::MathTools::ConvexHull6DPtr ConvexHullGenerator::CreateConvexHull(s if (facet->center) { - cout << "Center:" << facet->center[0] << "," << facet->center[1] << "," << facet->center[2] << "," << facet->center[3] << "," << facet->center[4] << "," << facet->center[5] << endl; + std::cout << "Center:" << facet->center[0] << "," << facet->center[1] << "," << facet->center[2] << "," << facet->center[3] << "," << facet->center[4] << "," << facet->center[5] << std::endl; } - cout << "distPlaneZero: " << f.distPlaneZero << ", distNormZero:" << f.distNormZero << ", QHULL_OFFSET:" << facet->offset << endl; - //cout << "Normal: " << f.normal.x << "," << f.normal.y << "," << f.normal.z << "," << f.normal.nx << "," << f.normal.ny << "," << f.normal.nz << endl; + std::cout << "distPlaneZero: " << f.distPlaneZero << ", distNormZero:" << f.distNormZero << ", QHULL_OFFSET:" << facet->offset << std::endl; + //cout << "Normal: " << f.normal.x << "," << f.normal.y << "," << f.normal.z << "," << f.normal.nx << "," << f.normal.ny << "," << f.normal.nz << std::endl; } #endif result->faces.push_back(f); nFacets++; } - /*cout << "QHULL result: created Vertices: " << storeResult.vertices.size() << endl; - cout << "QHULL result: created Faces: " << nFacets << endl; - cout << "QHULL result: nVertices: " << convexNumVert2 << endl; - cout << "QHULL result: nFactes: " << convexNumFaces2 << endl;*/ + /*cout << "QHULL result: created Vertices: " << storeResult.vertices.size() << std::endl; + std::cout << "QHULL result: created Faces: " << nFacets << std::endl; + std::cout << "QHULL result: nVertices: " << convexNumVert2 << std::endl; + std::cout << "QHULL result: nFactes: " << convexNumFaces2 << std::endl;*/ } simox_QHqh_freeqhull(qh, !simox_QHqh_ALL); @@ -38694,7 +38694,7 @@ VirtualRobot::MathTools::ConvexHull6DPtr ConvexHullGenerator::CreateConvexHull(s //clock_t endT = clock(); //long timeMS = (long)(((float)(endT - startT) / (float)CLOCKS_PER_SEC) * 1000.0); - //cout << __FUNCTION__ << ": Created 6D convex hull in " << timeMS << " ms" << endl; + //cout << __FUNCTION__ << ": Created 6D convex hull in " << timeMS << " ms" << std::endl; return result; } diff --git a/GraspPlanning/GraspPlanner/GenericGraspPlanner.cpp b/GraspPlanning/GraspPlanner/GenericGraspPlanner.cpp index 27926324721334703247efa183c477fb7d0ed1d4..58895f8e3ece1bc50b9605ccb082c92e05b36726 100644 --- a/GraspPlanning/GraspPlanner/GenericGraspPlanner.cpp +++ b/GraspPlanning/GraspPlanner/GenericGraspPlanner.cpp @@ -53,8 +53,8 @@ namespace GraspStudio GRASPSTUDIO_INFO << ": Searching " << nrGrasps << " grasps for EEF '" << approach->getEEF()->getName() << "' and object '" << graspQuality->getObject()->getName() << "'.\n" << "timeout set to " << timeOutMS << " ms.\n"; - GRASPSTUDIO_INFO << ": Approach movements are generated with " << approach->getName() << endl; - GRASPSTUDIO_INFO << ": Grasps are evaluated with " << graspQuality->getName() << endl; + GRASPSTUDIO_INFO << ": Approach movements are generated with " << approach->getName() << std::endl; + GRASPSTUDIO_INFO << ": Grasps are evaluated with " << graspQuality->getName() << std::endl; } while (!timeout() && nGraspsCreated < nrGrasps) @@ -81,7 +81,7 @@ namespace GraspStudio const auto dt = endt - startTime; const auto dtms = std::chrono::duration_cast<std::chrono::milliseconds>(dt); GRASPSTUDIO_INFO << ": created " << nGraspsCreated << " valid grasps in " << nLoop << " loops" - << "\n took " << dtms.count() << " ms " << endl; + << "\n took " << dtms.count() << " ms " << std::endl; } return nGraspsCreated; @@ -153,7 +153,7 @@ namespace GraspStudio if (colChecker->checkCollision(eef->createSceneObjectSet(), obstacles)) { - // GRASPSTUDIO_INFO << ": Collision detected before closing fingers" << endl; + // GRASPSTUDIO_INFO << ": Collision detected before closing fingers" << std::endl; //return VirtualRobot::GraspPtr(); bRes = false; } @@ -173,7 +173,7 @@ namespace GraspStudio { if (verbose) { - VR_INFO << "Low number of contacts, retreating hand (might be useful for a small object)" << endl; + VR_INFO << "Low number of contacts, retreating hand (might be useful for a small object)" << std::endl; } if (moveEEFAway(approach->getApproachDirGlobal(), 5.0f, 10)) { @@ -190,7 +190,7 @@ namespace GraspStudio if (colChecker->checkCollision(eef->createSceneObjectSet(), obstacles)) { - // GRASPSTUDIO_INFO << ": Collision detected after closing fingers" << endl; + // GRASPSTUDIO_INFO << ": Collision detected after closing fingers" << std::endl; //return VirtualRobot::GraspPtr(); bRes = false; } @@ -240,7 +240,7 @@ namespace GraspStudio { if (verbose) { - GRASPSTUDIO_INFO << ": ignoring grasp hypothesis, low number of contacts" << endl; + GRASPSTUDIO_INFO << ": ignoring grasp hypothesis, low number of contacts" << std::endl; } // result not valid due to low number of contacts float ms = getTimeMS(); @@ -283,7 +283,7 @@ namespace GraspStudio // found valid grasp if (verbose) { - GRASPSTUDIO_INFO << ": Found grasp with " << contacts.size() << " contacts, score: " << score << endl; + GRASPSTUDIO_INFO << ": Found grasp with " << contacts.size() << " contacts, score: " << score << std::endl; } float ms = getTimeMS(); diff --git a/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.cpp b/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.cpp index 9bf44e7e7c380b50218f5c50cb512a4d546c7176..aac7e4b82cbe4d4cdc65d5224f75c40ee4b7a59d 100644 --- a/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.cpp +++ b/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.cpp @@ -101,13 +101,13 @@ namespace GraspStudio Eigen::Vector3f centerPos = getMean(contacts); if (centerPos.hasNaN()) { - VR_ERROR << "No contacts" << endl; + VR_ERROR << "No contacts" << std::endl; return std::vector<Eigen::Matrix4f>(); } if (_config.verbose) { - cout << "using contact center pose:\n" << centerPos << endl; + std::cout << "using contact center pose:\n" << centerPos << std::endl; } return generatePoses(objectGP, math::Helpers::Pose(centerPos)); @@ -183,13 +183,13 @@ namespace GraspStudio Eigen::Vector3f centerPose = getMean(contacts); if (centerPose.hasNaN()) { - VR_ERROR << "No contacts" << endl; + VR_ERROR << "No contacts" << std::endl; return std::vector<Eigen::Matrix4f>(); } if (_config.verbose) { - cout << "using contact center pose:\n" << centerPose << endl; + std::cout << "using contact center pose:\n" << centerPose << std::endl; } return generatePoses(objectGP, math::Helpers::Pose(centerPose), numPoses); @@ -209,7 +209,7 @@ namespace GraspStudio if (!eef || !qm) { - VR_ERROR << "Missing parameters" << endl; + VR_ERROR << "Missing parameters" << std::endl; return result; } @@ -252,13 +252,13 @@ namespace GraspStudio if (!eef || !qm) { - VR_ERROR << "Missing parameters" << endl; + VR_ERROR << "Missing parameters" << std::endl; return {}; } if (!eef->getRobot()) { - VR_WARNING << "missing eef->robot" << endl; + VR_WARNING << "missing eef->robot" << std::endl; return {}; } @@ -328,12 +328,12 @@ namespace GraspStudio if (!grasp || !eef || !object || !qm) { - VR_WARNING << "missing parameters" << endl; + VR_WARNING << "missing parameters" << std::endl; return res; } if (!eef->getRobot()) { - VR_WARNING << "missing eef->robot" << endl; + VR_WARNING << "missing eef->robot" << std::endl; return res; } @@ -392,7 +392,7 @@ namespace GraspStudio Eigen::Vector3f mean = mean.Zero(); if (contacts.empty()) { - VR_ERROR << "No contacts" << endl; + VR_ERROR << "No contacts" << std::endl; return Eigen::Vector3f::Constant(std::nanf("")); } @@ -400,7 +400,7 @@ namespace GraspStudio { if (_config.verbose) { - cout << "contact point:" << i << ": \n" << contacts[i].contactPointObstacleGlobal << endl; + std::cout << "contact point:" << i << ": \n" << contacts[i].contactPointObstacleGlobal << std::endl; } mean += contacts[i].contactPointObstacleGlobal; } @@ -422,9 +422,9 @@ namespace GraspStudio std::ostream& operator<<(std::ostream& os, const GraspEvaluationPoseUncertainty::PoseEvalResults& rhs) { - os << "Robustness analysis" << endl; - os << "Num Poses Tested: \t" << rhs.numPosesTested << endl; - os << "Num Poses Valid: \t" << rhs.numValidPoses << endl; + os << "Robustness analysis" << std::endl; + os << "Num Poses Tested: \t" << rhs.numPosesTested << std::endl; + os << "Num Poses Valid: \t" << rhs.numValidPoses << std::endl; float colPercent = 0.0f; if (rhs.numPosesTested > 0) @@ -432,11 +432,11 @@ namespace GraspStudio colPercent = float(rhs.numColPoses) / float(rhs.numPosesTested) * 100.0f; } - os << "Num Poses initially in collision:\t" << rhs.numColPoses << " (" << colPercent << "%)" << endl; - os << "Avg Quality (only col freeposes):\t" << rhs.avgQuality << endl; - os << "FC rate (only col free poses): \t" << rhs.forceClosureRate * 100.0f << "%" << endl; - os << "Avg Quality (all poses): \t" << rhs.avgQualityCol << endl; - os << "FC rate (all poses): \t" << rhs.forceClosureRateCol * 100.0f << "%" << endl; + os << "Num Poses initially in collision:\t" << rhs.numColPoses << " (" << colPercent << "%)" << std::endl; + os << "Avg Quality (only col freeposes):\t" << rhs.avgQuality << std::endl; + os << "FC rate (only col free poses): \t" << rhs.forceClosureRate * 100.0f << "%" << std::endl; + os << "Avg Quality (all poses): \t" << rhs.avgQualityCol << std::endl; + os << "FC rate (all poses): \t" << rhs.forceClosureRateCol * 100.0f << "%" << std::endl; return os; } diff --git a/GraspPlanning/GraspQuality/GraspQualityMeasure.cpp b/GraspPlanning/GraspQuality/GraspQualityMeasure.cpp index 28e982d7fdbd2e6591bdc77e2af17f024a6fd144..98de5cda232c412fca38b11e3ae3127765b39cdc 100644 --- a/GraspPlanning/GraspQuality/GraspQualityMeasure.cpp +++ b/GraspPlanning/GraspQuality/GraspQualityMeasure.cpp @@ -43,7 +43,7 @@ namespace GraspStudio if (verbose) { - GRASPSTUDIO_INFO << ": object COM: << " << centerOfModel[0] << "," << centerOfModel[1] << "," << centerOfModel[2] << endl; + GRASPSTUDIO_INFO << ": object COM: << " << centerOfModel[0] << "," << centerOfModel[1] << "," << centerOfModel[2] << std::endl; } int nFaces = (int)model->faces.size(); @@ -81,7 +81,7 @@ namespace GraspStudio if (verbose) { - GRASPSTUDIO_INFO << ": Nr of sample object points:" << sampledObjectPoints.size() << endl; + GRASPSTUDIO_INFO << ": Nr of sample object points:" << sampledObjectPoints.size() << std::endl; } return (sampledObjectPoints.size() > 0); diff --git a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp index f15fe6f882c58a7ab394f3cbddffbea6c471253f..75d95333d03343a52e25bf840c08b999545fe257 100644 --- a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp +++ b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp @@ -90,7 +90,7 @@ namespace GraspStudio if (verbose && printAll) { - cout << "OWS contact points:" << endl; + std::cout << "OWS contact points:" << std::endl; } for (objPointsIter = sampledObjectPointsM.begin(); objPointsIter != sampledObjectPointsM.end(); objPointsIter++) @@ -110,7 +110,7 @@ namespace GraspStudio if (verbose && printAll) { - GRASPSTUDIO_INFO << " CENTER of OWS: " << endl; + GRASPSTUDIO_INFO << " CENTER of OWS: " << std::endl; MathTools::print(convexHullCenterOWS); } @@ -119,8 +119,8 @@ namespace GraspStudio if (verbose) { - GRASPSTUDIO_INFO << ": MinDistance to Center of OWS: " << minOffsetOWS << endl; - GRASPSTUDIO_INFO << ": Volume of OWS: " << volumeOWS << endl; + GRASPSTUDIO_INFO << ": MinDistance to Center of OWS: " << minOffsetOWS << std::endl; + GRASPSTUDIO_INFO << ": Volume of OWS: " << volumeOWS << std::endl; } OWSCalculated = true; @@ -145,7 +145,7 @@ namespace GraspStudio if (verbose && printAll) { - cout << "GWS contact points:" << endl; + std::cout << "GWS contact points:" << std::endl; } for (objPointsIter = contactPointsM.begin(); objPointsIter != contactPointsM.end(); objPointsIter++) @@ -165,7 +165,7 @@ namespace GraspStudio if (verbose && printAll) { - GRASPSTUDIO_INFO << " CENTER of GWS: " << endl; + GRASPSTUDIO_INFO << " CENTER of GWS: " << std::endl; MathTools::print(convexHullCenterGWS); } @@ -178,7 +178,7 @@ namespace GraspStudio if (verbose && printAll) { - cout << "Convex hull points for wrench calculation:" << endl; + std::cout << "Convex hull points for wrench calculation:" << std::endl; printContacts(points); } @@ -187,7 +187,7 @@ namespace GraspStudio if (verbose && printAll) { - cout << "Wrench points:" << endl; + std::cout << "Wrench points:" << std::endl; printContacts(wrenchPoints); } @@ -250,7 +250,7 @@ namespace GraspStudio while (iter != points.end()) { - cout << "# "; + std::cout << "# "; MathTools::print((*iter)); iter++; } @@ -260,7 +260,7 @@ namespace GraspStudio { if (!hull) { - GRASPSTUDIO_ERROR << "NULL data?!" << endl; + GRASPSTUDIO_ERROR << "NULL data?!" << std::endl; return VirtualRobot::MathTools::ContactPoint(); } @@ -271,7 +271,7 @@ namespace GraspStudio if (hull->vertices.size() == 0) { - cout << __FUNCTION__ << ": error, no vertices..." << endl; + std::cout << __FUNCTION__ << ": error, no vertices..." << std::endl; return resultCenter; } @@ -371,7 +371,7 @@ namespace GraspStudio if (nWrongFacets > 0) { - cout << __FUNCTION__ << " Warning: offset of " << nWrongFacets << " facets >0 (# of facets:" << ch->faces.size() << ")" << endl; + std::cout << __FUNCTION__ << " Warning: offset of " << nWrongFacets << " facets >0 (# of facets:" << ch->faces.size() << ")" << std::endl; } return fRes; @@ -386,13 +386,13 @@ namespace GraspStudio if (!convexHullGWS || convexHullGWS->vertices.size() == 0) { - cout << __FUNCTION__ << "No vertices in Grasp Wrench Space?! Maybe I was not initialized correctly..." << endl; + std::cout << __FUNCTION__ << "No vertices in Grasp Wrench Space?! Maybe I was not initialized correctly..." << std::endl; return 0.0; } if (volumeOWS <= 0 || convexHullGWS->volume <= 0) { - cout << __FUNCTION__ << "No Volumes in Wrench Space?! Maybe I was not initialized correctly..." << endl; + std::cout << __FUNCTION__ << "No Volumes in Wrench Space?! Maybe I was not initialized correctly..." << std::endl; return 0.0; } @@ -434,13 +434,13 @@ namespace GraspStudio if (!convexHullGWS || convexHullGWS->vertices.size() == 0) { - cout << __FUNCTION__ << "No vertices in Grasp Wrench Space?! Maybe I was not initialized correctly..." << endl; + std::cout << __FUNCTION__ << "No vertices in Grasp Wrench Space?! Maybe I was not initialized correctly..." << std::endl; return 0.0; } if (minOffsetOWS <= 0 || convexHullGWS->volume <= 0) { - cout << __FUNCTION__ << "No Volumes in Wrench Space?! Maybe I was not initialized correctly..." << endl; + std::cout << __FUNCTION__ << "No Volumes in Wrench Space?! Maybe I was not initialized correctly..." << std::endl; return 0.0; } @@ -459,11 +459,11 @@ namespace GraspStudio if (verbose) { - GRASPSTUDIO_INFO << endl; - cout << ": GWS volume : " << convexHullGWS->volume << endl; - cout << ": GWS min Offset: " << fResOffsetGWS << endl; - cout << ": OWS min Offset: " << fResOffsetOWS << endl; - cout << ": GraspQuality : " << graspQuality << endl; + GRASPSTUDIO_INFO << std::endl; + std::cout << ": GWS volume : " << convexHullGWS->volume << std::endl; + std::cout << ": GWS min Offset: " << fResOffsetGWS << std::endl; + std::cout << ": OWS min Offset: " << fResOffsetOWS << std::endl; + std::cout << ": GraspQuality : " << graspQuality << std::endl; } return true; diff --git a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp index f423297f813d79d25a49e1196052f24834574a5f..0d623546ad27bf7d9d615c95b6db3c2396d821a6 100644 --- a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp +++ b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp @@ -77,7 +77,7 @@ namespace GraspStudio if (verbose && printAll) { - cout << "GWS contact points:" << endl; + std::cout << "GWS contact points:" << std::endl; } for (objPointsIter = contactPointsM.begin(); objPointsIter != contactPointsM.end(); objPointsIter++) @@ -97,7 +97,7 @@ namespace GraspStudio if (verbose && printAll) { - GRASPSTUDIO_INFO << " CENTER of GWS: " << endl; + GRASPSTUDIO_INFO << " CENTER of GWS: " << std::endl; MathTools::print(convexHullCenterGWS); } @@ -110,7 +110,7 @@ namespace GraspStudio if (verbose && printAll) { - cout << "Convex hull points for wrench calculation:" << endl; + std::cout << "Convex hull points for wrench calculation:" << std::endl; printContacts(points); } @@ -119,7 +119,7 @@ namespace GraspStudio if (verbose && printAll) { - cout << "Wrench points:" << endl; + std::cout << "Wrench points:" << std::endl; printContacts(wrenchPoints); } @@ -182,7 +182,7 @@ namespace GraspStudio while (iter != points.end()) { - cout << "# "; + std::cout << "# "; MathTools::print((*iter)); iter++; } @@ -192,7 +192,7 @@ namespace GraspStudio { if (!hull) { - GRASPSTUDIO_ERROR << "NULL data?!" << endl; + GRASPSTUDIO_ERROR << "NULL data?!" << std::endl; return VirtualRobot::MathTools::ContactPoint(); } @@ -203,7 +203,7 @@ namespace GraspStudio if (hull->vertices.size() == 0) { - cout << __FUNCTION__ << ": error, no vertices..." << endl; + std::cout << __FUNCTION__ << ": error, no vertices..." << std::endl; return resultCenter; } @@ -303,7 +303,7 @@ namespace GraspStudio if (nWrongFacets > 0) { - cout << __FUNCTION__ << " Warning: offset of " << nWrongFacets << " facets >0 (# of facets:" << ch->faces.size() << ")" << endl; + std::cout << __FUNCTION__ << " Warning: offset of " << nWrongFacets << " facets >0 (# of facets:" << ch->faces.size() << ")" << std::endl; } return fRes; @@ -315,7 +315,7 @@ namespace GraspStudio if (!convexHullGWS || convexHullGWS->vertices.size() == 0) { - cout << __FUNCTION__ << "No vertices in Grasp Wrench Space?! Maybe I was not initialized correctly..." << endl; + std::cout << __FUNCTION__ << "No vertices in Grasp Wrench Space?! Maybe I was not initialized correctly..." << std::endl; return 0.0; } return convexHullGWS->volume; @@ -329,7 +329,7 @@ namespace GraspStudio if (!convexHullGWS || convexHullGWS->vertices.size() == 0) { - cout << __FUNCTION__ << "No vertices in Grasp Wrench Space?! Maybe I was not initialized correctly..." << endl; + std::cout << __FUNCTION__ << "No vertices in Grasp Wrench Space?! Maybe I was not initialized correctly..." << std::endl; return 0.0; } @@ -339,10 +339,10 @@ namespace GraspStudio if (verbose) { - GRASPSTUDIO_INFO << endl; - cout << ": GWS volume : " << convexHullGWS->volume << endl; - cout << ": GWS min Offset: " << fResOffsetGWS << endl; - cout << ": GraspQuality : " << graspQuality << endl; + GRASPSTUDIO_INFO << std::endl; + std::cout << ": GWS volume : " << convexHullGWS->volume << std::endl; + std::cout << ": GWS min Offset: " << fResOffsetGWS << std::endl; + std::cout << ": GraspQuality : " << graspQuality << std::endl; } return true; diff --git a/GraspPlanning/MeshConverter.cpp b/GraspPlanning/MeshConverter.cpp index 94d09c4a7cf6f2c27459f77ad3b336004784ba56..b796e01d6cefac45a81bd406fd212f2c3515aa5a 100644 --- a/GraspPlanning/MeshConverter.cpp +++ b/GraspPlanning/MeshConverter.cpp @@ -131,7 +131,7 @@ namespace GraspStudio if (verbose) { - VR_INFO << "Processing object with " << tm->faces.size() << " triangles" << endl; + VR_INFO << "Processing object with " << tm->faces.size() << " triangles" << std::endl; } // first create new object diff --git a/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.cpp b/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.cpp index 51ccb15fddd6e68a262cb159793d44271e120ce0..46da221341dfb6946630f44dd4b037a9e01f56a8 100644 --- a/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.cpp +++ b/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.cpp @@ -235,7 +235,7 @@ namespace GraspStudio if (!projectedHull) { - GRASPSTUDIO_ERROR << " Could not create hull of projected points, aborting..." << endl; + GRASPSTUDIO_ERROR << " Could not create hull of projected points, aborting..." << std::endl; return result; } @@ -243,7 +243,7 @@ namespace GraspStudio if (!hullV) { - GRASPSTUDIO_ERROR << " Could not create visualization of projected points, aborting..." << endl; + GRASPSTUDIO_ERROR << " Could not create visualization of projected points, aborting..." << std::endl; return result; } diff --git a/GraspPlanning/examples/GraspPlanner/GraspPlanner.cpp b/GraspPlanning/examples/GraspPlanner/GraspPlanner.cpp index 4a00cb2502b79cdd51c63c3f2e3a06c8ee679f1c..c8fe8337be3025ffa95e183d566d3d7f676571ba 100644 --- a/GraspPlanning/examples/GraspPlanner/GraspPlanner.cpp +++ b/GraspPlanning/examples/GraspPlanner/GraspPlanner.cpp @@ -17,11 +17,11 @@ using namespace VirtualRobot; int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "Simox Grasp Planner"); - cout << " --- START --- " << endl; - cout << endl << "Hint: You can start this demo for different hands:" << endl; - cout << "GraspPlanner --robot robots/iCub/iCub.xml --endeffector \"Left Hand\" --preshape \"Grasp Preshape\"" << endl; - cout << "GraspPlanner --robot robots/Shadow_Dexterous_Hand/shadowhand.xml --endeffector \"SHADOWHAND\" --preshape \"Grasp Preshape\"" << endl; - cout << "GraspPlanner --robot robots/Schunk_SAH/SAH_RightHand.xml --endeffector \"Right Hand\" --preshape \"Grasp Preshape\"" << endl; + std::cout << " --- START --- " << std::endl; + std::cout << endl << "Hint: You can start this demo for different hands:" << std::endl; + std::cout << "GraspPlanner --robot robots/iCub/iCub.xml --endeffector \"Left Hand\" --preshape \"Grasp Preshape\"" << std::endl; + std::cout << "GraspPlanner --robot robots/Shadow_Dexterous_Hand/shadowhand.xml --endeffector \"SHADOWHAND\" --preshape \"Grasp Preshape\"" << std::endl; + std::cout << "GraspPlanner --robot robots/Schunk_SAH/SAH_RightHand.xml --endeffector \"Right Hand\" --preshape \"Grasp Preshape\"" << std::endl; // --robot robots/iCub/iCub.xml --endeffector "Left Hand" --preshape "Grasp Preshape" std::string robot("robots/ArmarIII/ArmarIII.xml"); @@ -69,9 +69,9 @@ int main(int argc, char* argv[]) } - cout << "Using robot from " << robot << endl; - cout << "End effector:" << eef << ", preshape:" << preshape << endl; - cout << "Using object from " << object << endl; + std::cout << "Using robot from " << robot << std::endl; + std::cout << "End effector:" << eef << ", preshape:" << preshape << std::endl; + std::cout << "Using object from " << object << std::endl; GraspPlannerWindow rw(robot, eef, preshape, object); diff --git a/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.cpp b/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.cpp index 0a0c622be0b6d0cb3b619c6278dc0239e2368e37..343194de2fd83a50b1f894027b11f9c9faf624a9 100644 --- a/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.cpp +++ b/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.cpp @@ -45,7 +45,7 @@ using namespace GraspStudio; GraspPlannerWindow::GraspPlannerWindow(std::string& robFile, std::string& eefName, std::string& preshape, std::string& objFile) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; // init the random number generator this->robotFile = robFile; @@ -322,7 +322,7 @@ void GraspPlannerWindow::loadObject(const string& objFile) //Eigen::Vector3f minS,maxS; //object->getCollisionModel()->getTriMeshModel()->getSize(minS,maxS); - //cout << "minS: \n" << minS << "\nMaxS:\n" << maxS << endl; + //cout << "minS: \n" << minS << "\nMaxS:\n" << maxS << std::endl; qualityMeasure.reset(new GraspStudio::GraspQualityMeasureWrenchSpace(object)); //qualityMeasure->setVerbose(true); qualityMeasure->calculateObjectProperties(); @@ -347,7 +347,7 @@ void GraspPlannerWindow::loadRobot() if (!robot) { - VR_ERROR << " no robot at " << robotFile << endl; + VR_ERROR << " no robot at " << robotFile << std::endl; return; } @@ -382,7 +382,7 @@ void GraspPlannerWindow::plan() eefCloned->setPropagatingJointValuesEnabled(UI.checkBoxPropagateJointValues->isChecked()); int nr = planner->plan(nrGrasps, timeout); - VR_INFO << " Grasp planned:" << nr << endl; + VR_INFO << " Grasp planned:" << nr << std::endl; int start = static_cast<int>(grasps->getSize()) - nrGrasps - 1; if (start < 0) @@ -525,14 +525,14 @@ void GraspPlannerWindow::save() } catch (VirtualRobotException& e) { - cout << " ERROR while saving object" << endl; - cout << e.what(); + std::cout << " ERROR while saving object" << std::endl; + std::cout << e.what(); return; } if (!ok) { - cout << " ERROR while saving object" << endl; + std::cout << " ERROR while saving object" << std::endl; return; } } @@ -634,7 +634,7 @@ void GraspPlannerWindow::planObjectBatch() for (auto bin : histogramFC) { fs << ", " << static_cast<double>(bin) / graspSum; - cout << i << ": " << bin << ", " << graspSum << ", " << static_cast<double>(bin) / graspSum << std::endl; + std::cout << i << ": " << bin << ", " << graspSum << ", " << static_cast<double>(bin) / graspSum << std::endl; i++; } for (auto bin : histogramFCWithCollisions) diff --git a/GraspPlanning/examples/GraspQuality/GraspQualityDemo.cpp b/GraspPlanning/examples/GraspQuality/GraspQualityDemo.cpp index 89b18472b129e3fad16b1afb5eba114eb1e09bf8..dbbcd7665c10cccbbf649334df1d0d59125b1c9e 100644 --- a/GraspPlanning/examples/GraspQuality/GraspQualityDemo.cpp +++ b/GraspPlanning/examples/GraspQuality/GraspQualityDemo.cpp @@ -17,7 +17,7 @@ using namespace VirtualRobot; int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "Grasp Quality Demo"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; std::string robot("robots/ArmarIII/ArmarIII.xml"); VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(robot); @@ -45,8 +45,8 @@ int main(int argc, char* argv[]) } - cout << "Using robot from " << robot << endl; - cout << "Using object from " << object << endl; + std::cout << "Using robot from " << robot << std::endl; + std::cout << "Using object from " << object << std::endl; GraspQualityWindow rw(robot, object); diff --git a/GraspPlanning/examples/GraspQuality/GraspQualityWindow.cpp b/GraspPlanning/examples/GraspQuality/GraspQualityWindow.cpp index dd93de5320db7f8b262188e4bbbd66f1a944dd98..318ee82a2526edd43cc8403c03293410a97d445f 100644 --- a/GraspPlanning/examples/GraspQuality/GraspQualityWindow.cpp +++ b/GraspPlanning/examples/GraspQuality/GraspQualityWindow.cpp @@ -40,7 +40,7 @@ float TIMER_MS = 30.0f; GraspQualityWindow::GraspQualityWindow(std::string& robFile, std::string& objFile) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; this->robotFile = robFile; this->objectFile = objFile; @@ -259,14 +259,14 @@ void GraspQualityWindow::evalRobustness() int r = rand() % evalPoses.size(); Eigen::Matrix4f p = evalPoses.at(r); GraspStudio::GraspEvaluationPoseUncertainty::PoseEvalResult re = eval->evaluatePose(eef, object, p, qualityMeasure); - cout << "FC: " << re.forceClosure << endl; - cout << "init col: " << re.initialCollision << endl; - cout << "QUAL: " << re.quality << endl; + std::cout << "FC: " << re.forceClosure << std::endl; + std::cout << "init col: " << re.initialCollision << std::endl; + std::cout << "QUAL: " << re.quality << std::endl; */ GraspStudio::GraspEvaluationPoseUncertainty::PoseEvalResults re = eval->evaluatePoses(eef, object, evalPoses, qualityMeasure); if (eef && grasp) { - VR_INFO << "#### Robustness for eef " << eef->getName() << ", grasp " << grasp->getName() << endl; + VR_INFO << "#### Robustness for eef " << eef->getName() << ", grasp " << grasp->getName() << std::endl; } re.print(); } @@ -288,7 +288,7 @@ void GraspQualityWindow::evalRobustnessAll() c.init(varMM, varDeg); GraspStudio::GraspEvaluationPoseUncertaintyPtr eval(new GraspStudio::GraspEvaluationPoseUncertainty(c)); - VR_INFO << "Setting object pose to grasp " << grasp->getName() << endl; + VR_INFO << "Setting object pose to grasp " << grasp->getName() << std::endl; Eigen::Matrix4f pos = eef->getTcp()->getGlobalPose(); pos = grasp->getObjectTargetPoseGlobal(pos); object->setGlobalPose(pos); @@ -297,14 +297,14 @@ void GraspQualityWindow::evalRobustnessAll() eef->openActors(); contacts = eef->closeActors(object); - VR_INFO << contacts.size() << endl; + VR_INFO << contacts.size() << std::endl; if (contacts.size() == 0) { continue; } std::vector<Eigen::Matrix4f> evalPoses = eval->generatePoses(object->getGlobalPose(), contacts, numSamples); - VR_INFO << evalPoses.size() << endl; + VR_INFO << evalPoses.size() << std::endl; if (evalPoses.size() == 0) { continue; @@ -313,7 +313,7 @@ void GraspQualityWindow::evalRobustnessAll() GraspStudio::GraspEvaluationPoseUncertainty::PoseEvalResults re = eval->evaluatePoses(eef, object, evalPoses, qualityMeasure); if (eef && grasp) { - VR_INFO << "#### Robustness for eef " << eef->getName() << ", grasp " << grasp->getName() << endl; + VR_INFO << "#### Robustness for eef " << eef->getName() << ", grasp " << grasp->getName() << std::endl; } re.print(); @@ -343,13 +343,13 @@ void GraspQualityWindow::loadObject() } catch (...) { - VR_ERROR << "Could not load file " << objectFile << endl; + VR_ERROR << "Could not load file " << objectFile << std::endl; } } if (!object) { - VR_INFO << "Building standard box" << endl; + VR_INFO << "Building standard box" << std::endl; ObstaclePtr o = Obstacle::createBox(50.0f, 50.0f, 10.0f); object = ManipulationObject::createFromMesh(o->getVisualization()->getTriMeshModel()); } @@ -370,7 +370,7 @@ void GraspQualityWindow::loadRobot() if (!robot) { - VR_ERROR << " no robot at " << robotFile << endl; + VR_ERROR << " no robot at " << robotFile << std::endl; return; } @@ -396,7 +396,7 @@ void GraspQualityWindow::objectToGrasp() { if (object && grasp && eef->getTcp()) { - VR_INFO << "Setting object pose to grasp " << grasp->getName() << endl; + VR_INFO << "Setting object pose to grasp " << grasp->getName() << std::endl; Eigen::Matrix4f pos = eef->getTcp()->getGlobalPose(); pos = grasp->getObjectTargetPoseGlobal(pos); object->setGlobalPose(pos); @@ -413,17 +413,17 @@ void GraspQualityWindow::graspQuality() float volume = qualityMeasure->getVolumeGraspMeasure(); float epsilon = qualityMeasure->getGraspQuality(); bool fc = qualityMeasure->isGraspForceClosure(); - cout << "Grasp Quality (epsilon measure):" << epsilon << endl; - cout << "v measure:" << volume << endl; - cout << "Force closure:"; + std::cout << "Grasp Quality (epsilon measure):" << epsilon << std::endl; + std::cout << "v measure:" << volume << std::endl; + std::cout << "Force closure:"; if (fc) { - cout << "yes" << endl; + std::cout << "yes" << std::endl; } else { - cout << "no" << endl; + std::cout << "no" << std::endl; } } @@ -475,11 +475,11 @@ void GraspQualityWindow::setGraspComboBox() if (!grasps || grasps->getSize() == 0) { - VR_INFO << "No grasps found for eef " << eef->getName() << endl; + VR_INFO << "No grasps found for eef " << eef->getName() << std::endl; return; } - VR_INFO << "Found " << grasps->getSize() << " grasps for eef " << eef->getName() << endl; + VR_INFO << "Found " << grasps->getSize() << " grasps for eef " << eef->getName() << std::endl; for (size_t i = 0; i < grasps->getSize(); i++) { @@ -539,15 +539,15 @@ void GraspQualityWindow::updateObject(float x[6]) { if (object) { - //cout << "getGlobalPose robot:" << endl << robotEEF->getGlobalPose() << endl; - //cout << "getGlobalPose TCP:" << endl << robotEEF_EEF->getTcp()->getGlobalPose() << endl; + //cout << "getGlobalPose robot:" << endl << robotEEF->getGlobalPose() << std::endl; + //cout << "getGlobalPose TCP:" << endl << robotEEF_EEF->getTcp()->getGlobalPose() << std::endl; Eigen::Matrix4f m; MathTools::posrpy2eigen4f(x, m); m = object->getGlobalPose() * m; object->setGlobalPose(m); - cout << "object " << endl; - cout << m << endl; + std::cout << "object " << std::endl; + std::cout << m << std::endl; } @@ -721,22 +721,22 @@ void GraspQualityWindow::showGWS() // convex hull VirtualRobot::MathTools::ConvexHull6DPtr ch1 = GraspStudio::ConvexHullGenerator::CreateConvexHull(wrenchP); float minO = GraspStudio::GraspQualityMeasureWrenchSpace::minOffset(ch1); - cout << "minOffset:" << minO << endl; + std::cout << "minOffset:" << minO << std::endl; std::vector<MathTools::TriangleFace6D>::iterator faceIter; - cout << "Distances to Origin:" << endl; + std::cout << "Distances to Origin:" << std::endl; for (faceIter = ch1->faces.begin(); faceIter != ch1->faces.end(); faceIter++) { - cout << faceIter->distPlaneZero << ", "; + std::cout << faceIter->distPlaneZero << ", "; if (faceIter->distPlaneZero > 1e-4) { - cout << "<-- not force closure " << endl; + std::cout << "<-- not force closure " << std::endl; } } - cout << endl; + std::cout << std::endl; // ch visu GraspStudio::CoinConvexHullVisualizationPtr visu(new GraspStudio::CoinConvexHullVisualization(ch1, false)); SoSeparator* chV = visu->getCoinVisualization(); diff --git a/MotionPlanning/ApproachDiscretization.cpp b/MotionPlanning/ApproachDiscretization.cpp index e3d399c4249ca6642211cc67c9989f178cd08a22..cebd6a9bb278e77a416292b86f3157f73d91514d 100644 --- a/MotionPlanning/ApproachDiscretization.cpp +++ b/MotionPlanning/ApproachDiscretization.cpp @@ -20,7 +20,7 @@ namespace Saba //buildIVModel(); //clock_t tEnd = clock(); //long diffClock = (long)(((float)(tEnd - tStart) / (float)CLOCKS_PER_SEC) * 1000.0); - //cout << __FUNCTION__ << " Created Sphere in " << diffClock << "ms with " << sphere.m_Vertices.size() << " vertices and " << sphere.faces.size() << " faces "<< endl; + //cout << __FUNCTION__ << " Created Sphere in " << diffClock << "ms with " << sphere.m_Vertices.size() << " vertices and " << sphere.faces.size() << " faces "<< std::endl; } ApproachDiscretization::~ApproachDiscretization() @@ -104,7 +104,7 @@ namespace Saba } } - cout << __FUNCTION__ << " No face found ?!" << endl; + std::cout << __FUNCTION__ << " No face found ?!" << std::endl; return -1; } @@ -112,7 +112,7 @@ namespace Saba { if (faceId < 0 || faceId > (int)sphere.faces.size()) { - cout << __FUNCTION__ << "wrong face ID :" << faceId << endl; + std::cout << __FUNCTION__ << "wrong face ID :" << faceId << std::endl; return; } @@ -122,7 +122,7 @@ namespace Saba if (iter == faceIdToCSpaceNodesMapping[faceId].cspaceNodes.end()) { - cout << __FUNCTION__ << " Warning: Node " << node->ID << " is not mapped to face with id " << faceId << endl; + std::cout << __FUNCTION__ << " Warning: Node " << node->ID << " is not mapped to face with id " << faceId << std::endl; } else { @@ -131,7 +131,7 @@ namespace Saba } else { - cout << __FUNCTION__ << " Warning: Node " << node->ID << " is not mapped to face with id " << faceId << endl; + std::cout << __FUNCTION__ << " Warning: Node " << node->ID << " is not mapped to face with id " << faceId << std::endl; } } @@ -139,7 +139,7 @@ namespace Saba { if (!node) { - cout << __FUNCTION__ << "NULL data..." << endl; + std::cout << __FUNCTION__ << "NULL data..." << std::endl; return; } @@ -151,7 +151,7 @@ namespace Saba { if (faceId < 0 || faceId > (int)sphere.faces.size()) { - cout << __FUNCTION__ << "wrong face ID :" << faceId << endl; + std::cout << __FUNCTION__ << "wrong face ID :" << faceId << std::endl; return; } @@ -161,7 +161,7 @@ namespace Saba if (iter != faceIdToCSpaceNodesMapping[faceId].cspaceNodes.end()) { - cout << __FUNCTION__ << " Warning: Node " << node->ID << " is already mapped to face with id " << faceId << endl; + std::cout << __FUNCTION__ << " Warning: Node " << node->ID << " is already mapped to face with id " << faceId << std::endl; } else { @@ -180,7 +180,7 @@ namespace Saba { if (!node) { - cout << __FUNCTION__ << "NULL data..." << endl; + std::cout << __FUNCTION__ << "NULL data..." << std::endl; return; } diff --git a/MotionPlanning/CSpace/CSpace.cpp b/MotionPlanning/CSpace/CSpace.cpp index cf0d893c122eec1d045819bb4151a2b6237829f9..d85b8d0c2d16531fa5da4874ee0958988504b4f6 100644 --- a/MotionPlanning/CSpace/CSpace.cpp +++ b/MotionPlanning/CSpace/CSpace.cpp @@ -85,7 +85,7 @@ namespace Saba if (boundaryDist[i] == 0) { - SABA_WARNING << "Limits for joint " << robotJoints[i]->getName() << " not set correctly. Degenerated dimension (" << i << ") in C-Space." << endl; + SABA_WARNING << "Limits for joint " << robotJoints[i]->getName() << " not set correctly. Degenerated dimension (" << i << ") in C-Space." << std::endl; } } @@ -98,7 +98,7 @@ namespace Saba checkForBorderlessDimensions(checkForBorderlessDims); -// SABA_INFO << " dimension: " << dimension << ", random Seed: " << randomSeed << endl; +// SABA_INFO << " dimension: " << dimension << ", random Seed: " << randomSeed << std::endl; // allocate configs maxNodes = maxConfigs; @@ -175,7 +175,7 @@ namespace Saba if (bVerbose) { - SABA_INFO << "Checking " << s << " segments:" << endl; + SABA_INFO << "Checking " << s << " segments:" << std::endl; } for (unsigned int i = s - 1; i > 0; i--) @@ -186,7 +186,7 @@ namespace Saba if (bVerbose && t2 - t1 > 0) { - cout << "i:" << i << "->t:" << t2 - t1 << " , "; + std::cout << "i:" << i << "->t:" << t2 - t1 << " , "; } if (!bColFree) @@ -197,7 +197,7 @@ namespace Saba if (bVerbose) { - cout << endl; + std::cout << std::endl; } return true; @@ -411,7 +411,7 @@ namespace Saba // SABA_ASSERT(config.rows() == dimension) SABA_ASSERT(nextConfig.rows() == dimension) - SABA_WARNING << "NYI..." << endl; + SABA_WARNING << "NYI..." << std::endl; // todo : oobb updates in VirtualRobot return 0.0f; @@ -700,23 +700,23 @@ namespace Saba { if (config.rows() != dimension) { - SABA_ERROR << "Wrong dimensions..." << endl; + SABA_ERROR << "Wrong dimensions..." << std::endl; } streamsize pr = cout.precision(2); - cout << "<"; + std::cout << "<"; for (int i = 0; i < config.rows(); i++) { - cout << config[i]; + std::cout << config[i]; if (i != config.rows() - 1) { - cout << ","; + std::cout << ","; } } - cout << ">" << endl; + std::cout << ">" << std::endl; cout.precision(pr); } diff --git a/MotionPlanning/CSpace/CSpaceSampled.cpp b/MotionPlanning/CSpace/CSpaceSampled.cpp index 3ec07330c7411f8cd971f8cd5f60c8e3277e0df0..27a1fc21d4884ab45b5a84492bdbfd145d0b2efc 100644 --- a/MotionPlanning/CSpace/CSpaceSampled.cpp +++ b/MotionPlanning/CSpace/CSpaceSampled.cpp @@ -47,7 +47,7 @@ namespace Saba if (newRobot->getRootNode()->getCollisionChecker() != newColChecker) { - SABA_ERROR << ": Collision Checker instances do not match..." << endl; + SABA_ERROR << ": Collision Checker instances do not match..." << std::endl; return CSpaceSampledPtr(); } diff --git a/MotionPlanning/CSpace/CSpaceTree.cpp b/MotionPlanning/CSpace/CSpaceTree.cpp index 44b6fb543d15b3830eb7a4a5a269f828c022edd4..81d3ac64b9060175fcb949ccef5af05c05716d26 100644 --- a/MotionPlanning/CSpace/CSpaceTree.cpp +++ b/MotionPlanning/CSpace/CSpaceTree.cpp @@ -93,7 +93,7 @@ namespace Saba if (!getNode(idStart) || !getNode(idStart)) { - SABA_ERROR << "CSpaceTree::getPathDist: start or goal id not correct..." << endl; + SABA_ERROR << "CSpaceTree::getPathDist: start or goal id not correct..." << std::endl; return -1.0f; } @@ -278,7 +278,7 @@ namespace Saba if (it == nodes.end()) { - cout << "CSpaceTree::removeNode: node not in node vector ??? " << endl; + std::cout << "CSpaceTree::removeNode: node not in node vector ??? " << std::endl; return; } } @@ -302,7 +302,7 @@ namespace Saba if (nodes.size() == 0 || !cspace) { - SABA_WARNING << "no nodes in tree..." << endl; + SABA_WARNING << "no nodes in tree..." << std::endl; return 0; } diff --git a/MotionPlanning/CSpace/Sampler.cpp b/MotionPlanning/CSpace/Sampler.cpp index 2ce3810908670678767258ce2360c81c7c19f3f5..ca9cb09c5f1d668297e6a0c4fdf5314c56c31c15 100644 --- a/MotionPlanning/CSpace/Sampler.cpp +++ b/MotionPlanning/CSpace/Sampler.cpp @@ -25,7 +25,7 @@ namespace Saba { //for(unsigned int i = 0; i < dimension; i++) // pStoreConfig[i] = MathHelpers::getNormalRandom(mean[i], variance[i]); - cout << "todo" << endl; + std::cout << "todo" << std::endl; } @@ -33,7 +33,7 @@ namespace Saba { //for(unsigned int i = 0; i < dimension; i++) // pStoreConfig[i] = MathHelpers::getNormalRandom(mean[i], variance); - cout << "todo" << endl; + std::cout << "todo" << std::endl; } @@ -46,12 +46,12 @@ namespace Saba m_pMetricWeights = new float[dimension]; memcpy(m_pMetricWeights,pWeights,sizeof(float)*dimension); }*/ - cout << "todo" << endl; + std::cout << "todo" << std::endl; } void Sampler::disableMetricWeights() { - cout << "todo" << endl; + std::cout << "todo" << std::endl; } } diff --git a/MotionPlanning/Planner/BiRrt.cpp b/MotionPlanning/Planner/BiRrt.cpp index 07f4bde41a9733385519574f2f83acf014ec3b07..4ced01f45c4b89aaabfd8eca21ffff7fe52cd1e9 100644 --- a/MotionPlanning/Planner/BiRrt.cpp +++ b/MotionPlanning/Planner/BiRrt.cpp @@ -39,15 +39,15 @@ namespace Saba switch (rrtMode) { case eExtend: - cout << "-- ModeA: RRT-EXTEND" << endl; + std::cout << "-- ModeA: RRT-EXTEND" << std::endl; break; case eConnect: - cout << "-- ModeA: RRT-CONNECT" << endl; + std::cout << "-- ModeA: RRT-CONNECT" << std::endl; break; case eConnectCompletePath: - cout << "-- ModeA: RRT-CONNECT (only complete paths)" << endl; + std::cout << "-- ModeA: RRT-CONNECT (only complete paths)" << std::endl; break; default: @@ -57,15 +57,15 @@ namespace Saba switch (rrtMode2) { case eExtend: - cout << "-- ModeB: RRT-EXTEND" << endl; + std::cout << "-- ModeB: RRT-EXTEND" << std::endl; break; case eConnect: - cout << "-- ModeB: RRT-CONNECT" << endl; + std::cout << "-- ModeB: RRT-CONNECT" << std::endl; break; case eConnectCompletePath: - cout << "-- ModeB: RRT-CONNECT (only complete paths)" << endl; + std::cout << "-- ModeB: RRT-CONNECT (only complete paths)" << std::endl; break; default: @@ -204,7 +204,7 @@ namespace Saba if (!goalNode) { - SABA_ERROR << " no node for ID: " << lastIDB << endl; + SABA_ERROR << " no node for ID: " << lastIDB << std::endl; stopSearch = true; } else @@ -417,15 +417,15 @@ namespace Saba switch (rrtMode2) { case eExtend: - cout << "-- Mode2: RRT-EXTEND" << endl; + std::cout << "-- Mode2: RRT-EXTEND" << std::endl; break; case eConnect: - cout << "-- Mode2: RRT-CONNECT" << endl; + std::cout << "-- Mode2: RRT-CONNECT" << std::endl; break; case eConnectCompletePath: - cout << "-- Mode2: RRT-CONNECT (only complete paths)" << endl; + std::cout << "-- Mode2: RRT-CONNECT (only complete paths)" << std::endl; break; default: diff --git a/MotionPlanning/Planner/GraspIkRrt.cpp b/MotionPlanning/Planner/GraspIkRrt.cpp index 2c6b1fdb8b95bcda456accd67cad69ec87d5ae22..10f73afc2688efdbcd69c7485d1869a5603a2148 100644 --- a/MotionPlanning/Planner/GraspIkRrt.cpp +++ b/MotionPlanning/Planner/GraspIkRrt.cpp @@ -31,13 +31,13 @@ namespace Saba if (sampleGoalProbab < 0) { - SABA_WARNING << "Low value for sample goal probability, setting probability to 0" << endl; + SABA_WARNING << "Low value for sample goal probability, setting probability to 0" << std::endl; sampleGoalProbab = 0.0f; } if (sampleGoalProbab >= 1.0f) { - SABA_WARNING << "High value for sample goal probability, setting probability to 0.99" << endl; + SABA_WARNING << "High value for sample goal probability, setting probability to 0.99" << std::endl; sampleGoalProbab = 0.99f; } @@ -73,8 +73,8 @@ namespace Saba { // remove from working set graspSetWorking->removeGrasp(grasp); - SABA_INFO << endl << "Found new IK Solution: " << grasp->getName() << endl; - SABA_INFO << config << endl; + SABA_INFO << endl << "Found new IK Solution: " << grasp->getName() << std::endl; + SABA_INFO << config << std::endl; if (checkGoalConfig(config)) { @@ -82,7 +82,7 @@ namespace Saba } else { - SABA_INFO << "IK solution in collision " << endl; + SABA_INFO << "IK solution in collision " << std::endl; } } @@ -170,7 +170,7 @@ namespace Saba if (!goalNode) { - SABA_ERROR << " no node for ID: " << lastAddedID2 << endl; + SABA_ERROR << " no node for ID: " << lastAddedID2 << std::endl; stopSearch = true; } else diff --git a/MotionPlanning/Planner/GraspRrt.cpp b/MotionPlanning/Planner/GraspRrt.cpp index 6d13dea2abf4972ea3b289169b4b267ee1b5f89c..eac472b441df2330c08de8b79fadd561d1334dcb 100644 --- a/MotionPlanning/Planner/GraspRrt.cpp +++ b/MotionPlanning/Planner/GraspRrt.cpp @@ -125,7 +125,7 @@ namespace Saba if (!startNode) { - VR_ERROR << ": not initialized correctly..." << endl; + VR_ERROR << ": not initialized correctly..." << std::endl; return false; } @@ -181,11 +181,11 @@ namespace Saba break; case eGraspablePoseReached: - cout << endl << __FUNCTION__ << " -- FOUND A GRASPABLE POSITION (but score is not high enough) -- " << endl; + std::cout << endl << __FUNCTION__ << " -- FOUND A GRASPABLE POSITION (but score is not high enough) -- " << std::endl; if (grasps.size() <= 0) { - cout << __FUNCTION__ << ": Error, no grasp results stored..." << endl; + std::cout << __FUNCTION__ << ": Error, no grasp results stored..." << std::endl; } else { @@ -196,11 +196,11 @@ namespace Saba break; case eGoalReached: - cout << endl << __FUNCTION__ << " -- FOUND GOAL PATH (CONNECTION TO GRASPING POSITION VIA INV JACOBIAN) -- " << endl; + std::cout << endl << __FUNCTION__ << " -- FOUND GOAL PATH (CONNECTION TO GRASPING POSITION VIA INV JACOBIAN) -- " << std::endl; if (grasps.size() <= 0) { - cout << __FUNCTION__ << ": Error, no grasp results stored..." << endl; + std::cout << __FUNCTION__ << ": Error, no grasp results stored..." << std::endl; stopSearch = true; } @@ -357,30 +357,30 @@ namespace Saba void GraspRrt::printPerformanceResults() { - cout << endl << "=================== RESULTS ===================" << endl; + std::cout << endl << "=================== RESULTS ===================" << std::endl; std::cout << "Needed " << performanceMeasure.setupTimeMS << " ms for setup." << std::endl; std::cout << "Needed " << performanceMeasure.planningTimeMS << " ms for the complete planning process." << std::endl; std::cout << "Needed " << performanceMeasure.rrtTimeMS << " ms for building up the RRT." << std::endl; std::cout << "Needed " << performanceMeasure.moveTowardGraspPosesTimeMS << " ms for moving toward the grasp goals." << std::endl; std::cout << "Needed " << performanceMeasure.scoreGraspTimeMS << " ms for scoring the grasps." << std::endl; - cout << " Nr of grasp tries: " << performanceMeasure.numberOfMovementsTowardGraspPose << endl; + std::cout << " Nr of grasp tries: " << performanceMeasure.numberOfMovementsTowardGraspPose << std::endl; if (performanceMeasure.numberOfMovementsTowardGraspPose > 0) { - cout << " Avg Time for moving to grasping test position (without checking the grasp score):" << performanceMeasure.moveTowardGraspPosesTimeMS / (float)performanceMeasure.numberOfMovementsTowardGraspPose << " ms " << endl; + std::cout << " Avg Time for moving to grasping test position (without checking the grasp score):" << performanceMeasure.moveTowardGraspPosesTimeMS / (float)performanceMeasure.numberOfMovementsTowardGraspPose << " ms " << std::endl; } - cout << " Nr of grasp scorings: " << performanceMeasure.numberOfGraspScorings << endl; + std::cout << " Nr of grasp scorings: " << performanceMeasure.numberOfGraspScorings << std::endl; if (performanceMeasure.numberOfGraspScorings > 0) { - cout << " Avg Time for scoring a grasp:" << performanceMeasure.scoreGraspTimeMS / (float)performanceMeasure.numberOfGraspScorings << " ms " << endl; + std::cout << " Avg Time for scoring a grasp:" << performanceMeasure.scoreGraspTimeMS / (float)performanceMeasure.numberOfGraspScorings << " ms " << std::endl; } std::cout << "Created " << tree->getNrOfNodes() << " nodes." << std::endl; std::cout << "Collision Checks: " << colChecksOverall << std::endl; - cout << "=================== RESULTS ===================" << endl << endl; + std::cout << "=================== RESULTS ===================" << endl << std::endl; } bool GraspRrt::setStart(const Eigen::VectorXf& startVec) @@ -392,7 +392,7 @@ namespace Saba if (!Rrt::setStart(startVec) || !startNode) { - SABA_ERROR << " error initializing start node..." << endl; + SABA_ERROR << " error initializing start node..." << std::endl; return false; } @@ -401,15 +401,15 @@ namespace Saba if (verbose) { - cout << "GraspRrt::setStart" << endl; - cout << "startVec:"; + std::cout << "GraspRrt::setStart" << std::endl; + std::cout << "startVec:"; for (unsigned int i = 0; i < dimension; i++) { - cout << startNode->configuration[i] << ","; + std::cout << startNode->configuration[i] << ","; } - cout << endl; + std::cout << std::endl; } return true; @@ -459,13 +459,13 @@ namespace Saba if (l < 1e-8) { - cout << __FUNCTION__ << ":WARNING: length to target is small ... aborting " << endl; + std::cout << __FUNCTION__ << ":WARNING: length to target is small ... aborting " << std::endl; return false; } vecTarget_local.normalize(); float fAngle = VirtualRobot::MathTools::getAngle(vecTarget_local, vecZ_local); - //cout << "Angle : " << fAngle << endl; + //cout << "Angle : " << fAngle << std::endl; // c) rotation axis (is orthogonal on vecZ_local and vecTarget_local) Eigen::Vector3f rotAxis_local; @@ -499,7 +499,7 @@ namespace Saba if (!nnNode) { - cout << __FUNCTION__ << ": No good ranked node found..." << endl; + std::cout << __FUNCTION__ << ": No good ranked node found..." << std::endl; return eTrapped; } @@ -513,8 +513,8 @@ namespace Saba //MathTools::Eigen::Matrix4f2PosQuat(goalPose,m_pTmpPose); - //cout << "GoalGrasp:" << grasp->GetName() << endl; - //cout << "pos:" << m_pTmpPose[0] << "," << m_pTmpPose[1] << "," << m_pTmpPose[2] << endl; + //cout << "GoalGrasp:" << grasp->GetName() << std::endl; + //cout << "pos:" << m_pTmpPose[0] << "," << m_pTmpPose[1] << "," << m_pTmpPose[2] << std::endl; GraspRrt::MoveArmResult res = moveTowardsGoal(nnNode, goalPose, 300); clock_t timeEnd = clock(); float fMoveTime = ((float)(timeEnd - timeStart) / (float)CLOCKS_PER_SEC) * 1000.0f; @@ -523,7 +523,7 @@ namespace Saba if (verbose) { - cout << __FUNCTION__ << " - Time for Connect To Grasp Position:" << fMoveTime << endl; + std::cout << __FUNCTION__ << " - Time for Connect To Grasp Position:" << fMoveTime << std::endl; } return res; @@ -606,19 +606,19 @@ namespace Saba if (fGraspScore >= graspQualityMinScore) { - cout << __FUNCTION__ << ": found valid grasp (score:" << fGraspScore << ")" << endl; + std::cout << __FUNCTION__ << ": found valid grasp (score:" << fGraspScore << ")" << std::endl; return eGoalReached; } else if (fGraspScore > 0.0f) { - cout << __FUNCTION__ << ": found valid grasp (score:" << fGraspScore << ")" << endl; + std::cout << __FUNCTION__ << ": found valid grasp (score:" << fGraspScore << ")" << std::endl; return eGraspablePoseReached; } else { if (verbose) { - cout << __FUNCTION__ << ": aborting moveArmToGraspPos, Collision but no graspable config " << endl; + std::cout << __FUNCTION__ << ": aborting moveArmToGraspPos, Collision but no graspable config " << std::endl; } return eCollision_Environment; @@ -635,7 +635,7 @@ namespace Saba { if (verbose) { - cout << __FUNCTION__ << ": aborting moveArmToGraspPos, checkPath fails, todo: check GRASP of last valid config.. " << endl; + std::cout << __FUNCTION__ << ": aborting moveArmToGraspPos, checkPath fails, todo: check GRASP of last valid config.. " << std::endl; } return eCollision_Environment; @@ -646,7 +646,7 @@ namespace Saba if (!r) { - cout << __FUNCTION__ << ": aborting moveArmToGraspPos, appendPath failed?! " << endl; + std::cout << __FUNCTION__ << ": aborting moveArmToGraspPos, appendPath failed?! " << std::endl; return eError; } @@ -666,7 +666,7 @@ namespace Saba { if (verbose) { - cout << __FUNCTION__ << ": Stop no dist improvement: last: " << lastDist << ", dist: " << dist << endl; + std::cout << __FUNCTION__ << ": Stop no dist improvement: last: " << lastDist << ", dist: " << dist << std::endl; } return eTrapped; @@ -678,14 +678,14 @@ namespace Saba case eJointBoundaryViolation: if (verbose) { - cout << __FUNCTION__ << " Stopping: Joint limits reached " << endl; + std::cout << __FUNCTION__ << " Stopping: Joint limits reached " << std::endl; } return eTrapped; break; default: - cout << __FUNCTION__ << ": result nyi " << res << endl; + std::cout << __FUNCTION__ << ": result nyi " << res << std::endl; break; } @@ -693,7 +693,7 @@ namespace Saba { if (verbose) { - cout << __FUNCTION__ << " grasp goal position reached, dist: " << dist << endl; + std::cout << __FUNCTION__ << " grasp goal position reached, dist: " << dist << std::endl; } // check grasp score of last valid config @@ -701,19 +701,19 @@ namespace Saba if (fGraspScore >= graspQualityMinScore) { - cout << __FUNCTION__ << ": found valid grasp (score:" << fGraspScore << ")" << endl; + std::cout << __FUNCTION__ << ": found valid grasp (score:" << fGraspScore << ")" << std::endl; return eGoalReached; } else if (fGraspScore > 0.0f) { - cout << __FUNCTION__ << ": found valid grasp (score:" << fGraspScore << ")" << endl; + std::cout << __FUNCTION__ << ": found valid grasp (score:" << fGraspScore << ")" << std::endl; return eGraspablePoseReached; } else { if (verbose) { - cout << __FUNCTION__ << ": aborting moveArmToGraspPos, goal pos reached but zero grasp score " << endl; + std::cout << __FUNCTION__ << ": aborting moveArmToGraspPos, goal pos reached but zero grasp score " << std::endl; } return eTrapped; @@ -723,7 +723,7 @@ namespace Saba if (verbose) { - cout << __FUNCTION__ << " max lops reached, dist: " << dist << endl; + std::cout << __FUNCTION__ << " max lops reached, dist: " << dist << std::endl; } return eTrapped; @@ -736,8 +736,8 @@ namespace Saba float angle; //MathHelpers::quat2AxisAngle(&(pPosQuat[3]),axis,&angle); VirtualRobot::MathTools::eigen4f2axisangle(p, axis, angle); - //cout << "Delta in Workspace: pos:" << deltaX << "," << deltaY << "," << deltaZ << " Dist: " << distPos << endl; - //cout << "Delta in Workspace: ori:" << angle << endl; + //cout << "Delta in Workspace: pos:" << deltaX << "," << deltaY << "," << deltaZ << " Dist: " << distPos << std::endl; + //cout << "Delta in Workspace: ori:" << angle << std::endl; float distOri = fabs(angle); float factorPos = 1.0f; @@ -785,21 +785,21 @@ namespace Saba deltaPose.block(0, 3, 3, 1) = goalPose.block(0, 3, 3, 1) - currentPose.block(0, 3, 3, 1); /* - cout << "Current pose:" << endl; - cout << currentPose << endl;; - cout << "goal pose:" << endl; - cout << goalPose << endl;; - cout << "delta pose:" << endl; - cout << deltaPose << endl;; + std::cout << "Current pose:" << std::endl; + std::cout << currentPose << std::endl;; + std::cout << "goal pose:" << std::endl; + std::cout << goalPose << std::endl;; + std::cout << "delta pose:" << std::endl; + std::cout << deltaPose << std::endl;; */ limitWorkspaceStep(deltaPose); //MathTools::PosQuat2PosRPY(pDeltaPosQuat_Global,pDeltaPosRPY_Global); /* - cout << "delta pose (limit):" << endl; - cout << deltaPose << endl;; - cout << "---------------" << endl; + std::cout << "delta pose (limit):" << std::endl; + std::cout << deltaPose << std::endl;; + std::cout << "---------------" << std::endl; */ return moveArmDiffKin(deltaPose, storeCSpaceConf); @@ -926,15 +926,15 @@ namespace Saba { if (verbose) { - cout << __FUNCTION__ << ": Low number of contacts -> Zero Grasp Score " << endl; - cout << "Fingers: " ; + std::cout << __FUNCTION__ << ": Low number of contacts -> Zero Grasp Score " << std::endl; + std::cout << "Fingers: " ; for (auto & contact : contacts) { - cout << contact.actor->getName() << ", "; + std::cout << contact.actor->getName() << ", "; } - cout << endl; + std::cout << std::endl; } clock_t timeEnd = clock(); @@ -956,9 +956,9 @@ namespace Saba fScore = graspQualityMeasure->getGraspQuality(); bool isFC = graspQualityMeasure->isValid(); - cout << __FUNCTION__ << ": Grasp Measure Score:" << fScore << endl; - cout << __FUNCTION__ << ": IsGraspForceClosure/isValid:" << isFC << endl; - cout << __FUNCTION__ << ": Nr of Contacts Score:" << fScoreContacts << endl; + std::cout << __FUNCTION__ << ": Grasp Measure Score:" << fScore << std::endl; + std::cout << __FUNCTION__ << ": IsGraspForceClosure/isValid:" << isFC << std::endl; + std::cout << __FUNCTION__ << ": Nr of Contacts Score:" << fScoreContacts << std::endl; if (!isFC) { @@ -1003,7 +1003,7 @@ namespace Saba SbVec3f VecCOM; SoSeparator* pObjSep = m_pManipulationObject->GetIVModel(); m_pManipulationObject->getCenterOfMass(VecCOM); - cout << "Center of Mass " << VecCOM[0] << "," << VecCOM[1] << "," << VecCOM[2] << endl; + std::cout << "Center of Mass " << VecCOM[0] << "," << VecCOM[1] << "," << VecCOM[2] << std::endl; SoGetBoundingBoxAction *objectBBAction = new SoGetBoundingBoxAction(SbViewportRegion(0, 0)); SbBox3f objectBB; if (pObjSep==NULL) @@ -1026,11 +1026,11 @@ namespace Saba void GraspRrt::printGraspInfo(GraspInfo& GrInfo) { - cout << "Grasp Info:" << endl; - cout << " Distance to object: " << GrInfo.distanceToObject << endl; - cout << " Grasp score: " << GrInfo.graspScore << endl; - cout << " RRT Node ID: " << GrInfo.rrtNodeId << endl; - cout << " Contacts stored: " << GrInfo.contacts.size() << endl; + std::cout << "Grasp Info:" << std::endl; + std::cout << " Distance to object: " << GrInfo.distanceToObject << std::endl; + std::cout << " Grasp score: " << GrInfo.graspScore << std::endl; + std::cout << " RRT Node ID: " << GrInfo.rrtNodeId << std::endl; + std::cout << " Contacts stored: " << GrInfo.contacts.size() << std::endl; } @@ -1062,7 +1062,7 @@ namespace Saba std::cout << " RNS: " << rns->getName() << std::endl; } - cout << " Cart Step Size: " << cartSamplingPosStepSize << ", Orientational step size: " << cartSamplingPosStepSize << endl; + std::cout << " Cart Step Size: " << cartSamplingPosStepSize << ", Orientational step size: " << cartSamplingPosStepSize << std::endl; Rrt::printConfig(true); if (!printOnlyParams) @@ -1089,7 +1089,7 @@ namespace Saba if (nIndex < 0 || nIndex >= (int)grasps.size()) { - cout << __FUNCTION__ << ": index out of range: " << nIndex << endl; + std::cout << __FUNCTION__ << ": index out of range: " << nIndex << std::endl; graspInfoMutex.unlock(); return false; } diff --git a/MotionPlanning/Planner/PlanningThread.cpp b/MotionPlanning/Planner/PlanningThread.cpp index 9d756658788dde8289ff5ba24155f3896ac7f066..2843fbccff79da29685729e01613eca27211091d 100644 --- a/MotionPlanning/Planner/PlanningThread.cpp +++ b/MotionPlanning/Planner/PlanningThread.cpp @@ -88,7 +88,7 @@ namespace Saba { if (!threadStarted) { - VR_WARNING << "Thread should be in started mode?!" << endl; + VR_WARNING << "Thread should be in started mode?!" << std::endl; } VR_ASSERT(planner); diff --git a/MotionPlanning/Planner/Rrt.cpp b/MotionPlanning/Planner/Rrt.cpp index 14c5139c08b1928f9e1dce920e99852e265da729..c3f10d51c5833e1e056ab49b0417d5ab07abcc79 100644 --- a/MotionPlanning/Planner/Rrt.cpp +++ b/MotionPlanning/Planner/Rrt.cpp @@ -22,13 +22,13 @@ namespace Saba if (probabilityExtendToGoal <= 0) { - SABA_ERROR << " probabilityExtendToGoal is wrong: " << probabilityExtendToGoal << endl; + SABA_ERROR << " probabilityExtendToGoal is wrong: " << probabilityExtendToGoal << std::endl; probabilityExtendToGoal = 0.1f; } if (probabilityExtendToGoal >= 1.0f) { - SABA_ERROR << " probabilityExtendToGoal is wrong: " << probabilityExtendToGoal << endl; + SABA_ERROR << " probabilityExtendToGoal is wrong: " << probabilityExtendToGoal << std::endl; probabilityExtendToGoal = 0.9f; } @@ -56,15 +56,15 @@ namespace Saba switch (rrtMode) { case eExtend: - cout << "-- Mode: RRT-EXTEND" << endl; + std::cout << "-- Mode: RRT-EXTEND" << std::endl; break; case eConnect: - cout << "-- Mode: RRT-CONNECT" << endl; + std::cout << "-- Mode: RRT-CONNECT" << std::endl; break; case eConnectCompletePath: - cout << "-- Mode: RRT-CONNECT (only complete paths)" << endl; + std::cout << "-- Mode: RRT-CONNECT (only complete paths)" << std::endl; break; default: @@ -136,14 +136,14 @@ namespace Saba if (!goalNode) { - SABA_ERROR << " no node for ID: " << lastAddedID << endl; + SABA_ERROR << " no node for ID: " << lastAddedID << std::endl; stopSearch = true; } else { if (!goalConfig.isApprox(goalNode->configuration)) { - SABA_WARNING << "GoalConfig: (" << goalConfig << ") != goalNode (" << goalNode->configuration << ")" << endl; + SABA_WARNING << "GoalConfig: (" << goalConfig << ") != goalNode (" << goalNode->configuration << ")" << std::endl; } //SABA_ASSERT(goalConfig.isApprox(goalNode->configuration)); @@ -376,15 +376,15 @@ namespace Saba switch (rrtMode) { case eExtend: - cout << "-- Mode: RRT-EXTEND" << endl; + std::cout << "-- Mode: RRT-EXTEND" << std::endl; break; case eConnect: - cout << "-- Mode: RRT-CONNECT" << endl; + std::cout << "-- Mode: RRT-CONNECT" << std::endl; break; case eConnectCompletePath: - cout << "-- Mode: RRT-CONNECT (only complete paths)" << endl; + std::cout << "-- Mode: RRT-CONNECT (only complete paths)" << std::endl; break; default: @@ -407,7 +407,7 @@ namespace Saba if (tree->getNrOfNodes() > 0) { - SABA_WARNING << "Removing all nodes from tree..." << endl; + SABA_WARNING << "Removing all nodes from tree..." << std::endl; tree->reset(); } diff --git a/MotionPlanning/PostProcessing/ElasticBandProcessor.cpp b/MotionPlanning/PostProcessing/ElasticBandProcessor.cpp index 5bf0132eaddac774b6e995bf1b0dbdf72cb54f97..df1c327549510c12de2952cd004bf8c76c88af84 100644 --- a/MotionPlanning/PostProcessing/ElasticBandProcessor.cpp +++ b/MotionPlanning/PostProcessing/ElasticBandProcessor.cpp @@ -27,7 +27,7 @@ using namespace VirtualRobot; rns = path->getCSpace()->getRobotNodeSet(); VR_ASSERT(rns && rns->getSize()>0); - VR_INFO << "using rns " << rns->getName() << endl; + VR_INFO << "using rns " << rns->getName() << std::endl; stopOptimization = false; colChecker = node->getRobot()->getCollisionChecker(); @@ -93,11 +93,11 @@ using namespace VirtualRobot; if (verbose) { - VR_INFO << "Obstacle dist:" << d << endl; + VR_INFO << "Obstacle dist:" << d << std::endl; } if (d==0) { - VR_ERROR << "Collision..." << endl; + VR_ERROR << "Collision..." << std::endl; return false; } @@ -185,32 +185,32 @@ using namespace VirtualRobot; if (!getObstacleForce(fObstacle)) { - VR_WARNING << "Could not get obstacle force " << i << endl; + VR_WARNING << "Could not get obstacle force " << i << std::endl; continue; } if (verbose) - VR_INFO << "obstacle workspace force: " << fObstacle.transpose() << endl; + VR_INFO << "obstacle workspace force: " << fObstacle.transpose() << std::endl; if (!getCSpaceForce(fObstacle, fcObstacle, factorCSpaceObstacleForce, maxCSpaceObstacleForce)) { - VR_WARNING << "Could not get obstacle cspace force " << i << endl; + VR_WARNING << "Could not get obstacle cspace force " << i << std::endl; continue; } if (verbose) - VR_INFO << "obstacle c-space force: " << fcObstacle.transpose() << endl; + VR_INFO << "obstacle c-space force: " << fcObstacle.transpose() << std::endl; getNeighborCForce(before, act, next, fcNeighbor); if (verbose) { Eigen::Vector3f fn; getWSpaceForce(fcNeighbor, fn); - VR_INFO << "neighbor workspace force: " << fn.transpose() << endl; - VR_INFO << "neighbor c-space force: " << fcNeighbor.transpose() << endl; + VR_INFO << "neighbor workspace force: " << fn.transpose() << std::endl; + VR_INFO << "neighbor c-space force: " << fcNeighbor.transpose() << std::endl; } fc = fcObstacle + fcNeighbor; fc = fc.cwiseProduct(weights); if (verbose) - VR_INFO << "resulting c-space force: " << fc.transpose() << endl; + VR_INFO << "resulting c-space force: " << fc.transpose() << std::endl; optimizedPath->getPointRef(i) += fc; } @@ -261,7 +261,7 @@ using namespace VirtualRobot; Eigen::VectorXf fcExt; if (!optimizedPath || optimizedPath->getNrOfPoints()<=i) { - VR_WARNING << "no path or wrong index" << endl; + VR_WARNING << "no path or wrong index" << std::endl; internalForce.setZero(); externalForce.setZero(); return; @@ -284,7 +284,7 @@ using namespace VirtualRobot; if (!getObstacleForce(externalForce)) { - VR_WARNING << "Could not get obstacle force" << endl; + VR_WARNING << "Could not get obstacle force" << std::endl; } // we need to apply factors and max -> transform to cspace and back to wspace @@ -294,7 +294,7 @@ using namespace VirtualRobot; getNeighborCForce(before, act, next, fcNeighbor); if (!getWSpaceForce(fcNeighbor, internalForce)) { - VR_WARNING << "Could not get internal cspace force " << endl; + VR_WARNING << "Could not get internal cspace force " << std::endl; } } @@ -310,17 +310,17 @@ using namespace VirtualRobot; { if (!elasticBandLoop()) { - VR_ERROR << "Error in loop, aborting..." << endl; + VR_ERROR << "Error in loop, aborting..." << std::endl; break; } if (!checkRemoveNodes()) { - VR_ERROR << "Error in remove, aborting..." << endl; + VR_ERROR << "Error in remove, aborting..." << std::endl; break; } if (!checkNewNodes()) { - VR_ERROR << "Error in add, aborting..." << endl; + VR_ERROR << "Error in add, aborting..." << std::endl; break; } } diff --git a/MotionPlanning/PostProcessing/PathProcessingThread.cpp b/MotionPlanning/PostProcessing/PathProcessingThread.cpp index d8977449e9400511289be8bc635782f401ebfc10..dc3d63d5abea18bad0512a80f992d6ac724cd3f8 100644 --- a/MotionPlanning/PostProcessing/PathProcessingThread.cpp +++ b/MotionPlanning/PostProcessing/PathProcessingThread.cpp @@ -93,7 +93,7 @@ namespace Saba { if (!threadStarted) { - VR_WARNING << "Thread should be in started mode?!" << endl; + VR_WARNING << "Thread should be in started mode?!" << std::endl; } VR_ASSERT(pathProcessor); diff --git a/MotionPlanning/PostProcessing/ShortcutProcessor.cpp b/MotionPlanning/PostProcessing/ShortcutProcessor.cpp index 665932febc97a236493a914d5f1f6e40af910f22..d79344b3419b14c3644b37f238e3e01bd2a9e468 100644 --- a/MotionPlanning/PostProcessing/ShortcutProcessor.cpp +++ b/MotionPlanning/PostProcessing/ShortcutProcessor.cpp @@ -23,7 +23,7 @@ namespace Saba { if (!path || !cspace) { - SABA_ERROR << "NULL data" << endl; + SABA_ERROR << "NULL data" << std::endl; return 0; } @@ -84,7 +84,7 @@ namespace Saba std::cout << "-- erased intermediate positions, distPath startIndex to (startIndex+1): " << distPathtest << std::endl; } - /*cout << "all2:" << endl; + /*cout << "all2:" << std::endl; optimizedPath->print();*/ Eigen::VectorXf s = optimizedPath->getPoint(startIndex); @@ -97,16 +97,16 @@ namespace Saba if (intermediatePath->getNrOfPoints() > 2) { newP = intermediatePath->getNrOfPoints() - 2; - /*cout << "before:" << endl; + /*cout << "before:" << std::endl; optimizedPath->print(); - cout << "interm path:" << endl; + std::cout << "interm path:" << std::endl; intermediatePath->print();*/ intermediatePath->erasePosition(intermediatePath->getNrOfPoints() - 1); intermediatePath->erasePosition(0); - /*cout << "interm path without start end:" << endl; + /*cout << "interm path without start end:" << std::endl; intermediatePath->print();*/ optimizedPath->insertTrajectory(startIndex + 1, intermediatePath); - /*cout << "after:" << endl; + /*cout << "after:" << std::endl; optimizedPath->print(); */ } @@ -310,7 +310,7 @@ namespace Saba { if (verbose) { - cout << "Path is not shorter..." << endl; + std::cout << "Path is not shorter..." << std::endl; } return false; diff --git a/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.cpp b/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.cpp index a84d55c430db5a74c4534df3b0cf31d045d9fe01..ecf5dd8feec4d59d1260051fbabc937d26570a5f 100644 --- a/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.cpp +++ b/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.cpp @@ -83,7 +83,7 @@ namespace Saba if (path->getDimension() != robotNodeSet->getSize()) { - VR_ERROR << " Dimensions do not match: " << path->getDimension() << "!=" << robotNodeSet->getSize() << endl; + VR_ERROR << " Dimensions do not match: " << path->getDimension() << "!=" << robotNodeSet->getSize() << std::endl; return false; } @@ -197,7 +197,7 @@ namespace Saba if (tree->getDimension() != robotNodeSet->getSize()) { - VR_ERROR << " Dimensions do not match: " << tree->getDimension() << "!=" << robotNodeSet->getSize() << endl; + VR_ERROR << " Dimensions do not match: " << tree->getDimension() << "!=" << robotNodeSet->getSize() << std::endl; return false; } @@ -360,7 +360,7 @@ namespace Saba { if (c.rows() != robotNodeSet->getSize()) { - VR_ERROR << " Dimensions do not match: " << c.rows() << "!=" << robotNodeSet->getSize() << endl; + VR_ERROR << " Dimensions do not match: " << c.rows() << "!=" << robotNodeSet->getSize() << std::endl; return false; } diff --git a/MotionPlanning/Visualization/RrtWorkspaceVisualization.cpp b/MotionPlanning/Visualization/RrtWorkspaceVisualization.cpp index 82cbb5eb56e7867e0a733bc3aaa7c71c550c15e4..a3cecfbe84368250a3c39c8655d1b1b5149337ec 100644 --- a/MotionPlanning/Visualization/RrtWorkspaceVisualization.cpp +++ b/MotionPlanning/Visualization/RrtWorkspaceVisualization.cpp @@ -115,7 +115,7 @@ namespace Saba if (!TCPNode) { - VR_ERROR << "No node with name " << TCPName << " available in robot.." << endl; + VR_ERROR << "No node with name " << TCPName << " available in robot.." << std::endl; } } diff --git a/MotionPlanning/examples/GraspRRT/GraspRrtDemo.cpp b/MotionPlanning/examples/GraspRRT/GraspRrtDemo.cpp index 1aefc951aee0d8b38e86037947518e5d1bb44b27..2625a4ad29a20667be1c2abf2e640f8811902956 100644 --- a/MotionPlanning/examples/GraspRRT/GraspRrtDemo.cpp +++ b/MotionPlanning/examples/GraspRRT/GraspRrtDemo.cpp @@ -28,7 +28,7 @@ int main(int argc, char** argv) { VirtualRobot::init(argc, argv, "GraspRrtDemo"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; std::string filenameScene("/scenes/examples/GraspRrt/planning.xml"); VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(filenameScene); @@ -145,18 +145,18 @@ int main(int argc, char** argv) } - cout << "Using scene: " << filenameScene << endl; - cout << "Using start config: <" << startConfig << ">" << endl; - cout << "Using target object: <" << goalObject << ">" << endl; - cout << "Using environment collision model set: <" << colModel3 << ">" << endl; - cout << "Set 1:" << endl; - cout << "\t Using RobotNodeSet for planning: <" << rnsName << ">" << endl; - cout << "\t Using EEF for grasping: <" << eefName << ">" << endl; - cout << "\t Using robot collision model sets: <" << colModel1 << "> and <" << colModel2 << ">" << endl; - cout << "Set 2:" << endl; - cout << "\t Using RobotNodeSet for planning: <" << rnsNameB << ">" << endl; - cout << "\t Using EEF for grasping: <" << eefNameB << ">" << endl; - cout << "\t Using robot collision model sets: <" << colModel1B << "> and <" << colModel2B << ">" << endl; + std::cout << "Using scene: " << filenameScene << std::endl; + std::cout << "Using start config: <" << startConfig << ">" << std::endl; + std::cout << "Using target object: <" << goalObject << ">" << std::endl; + std::cout << "Using environment collision model set: <" << colModel3 << ">" << std::endl; + std::cout << "Set 1:" << std::endl; + std::cout << "\t Using RobotNodeSet for planning: <" << rnsName << ">" << std::endl; + std::cout << "\t Using EEF for grasping: <" << eefName << ">" << std::endl; + std::cout << "\t Using robot collision model sets: <" << colModel1 << "> and <" << colModel2 << ">" << std::endl; + std::cout << "Set 2:" << std::endl; + std::cout << "\t Using RobotNodeSet for planning: <" << rnsNameB << ">" << std::endl; + std::cout << "\t Using EEF for grasping: <" << eefNameB << ">" << std::endl; + std::cout << "\t Using robot collision model sets: <" << colModel1B << "> and <" << colModel2B << ">" << std::endl; GraspRrtWindow rw(filenameScene, startConfig, goalObject, rnsName, rnsNameB, eefName, eefNameB, colModel1, colModel1B, colModel2, colModel2B, colModel3); diff --git a/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp b/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp index 7d04ffdc1549d2135a5730293cd6429562bb6e04..20b0f099b814650e74f5565217aadf2b993b8094 100644 --- a/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp +++ b/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp @@ -43,7 +43,7 @@ GraspRrtWindow::GraspRrtWindow(const std::string& sceneFile, const std::string& const std::string& colModelEnv) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; this->sceneFile = sceneFile; @@ -283,7 +283,7 @@ void GraspRrtWindow::loadScene() if (!scene) { - VR_ERROR << " no scene ..." << endl; + VR_ERROR << " no scene ..." << std::endl; return; } @@ -291,7 +291,7 @@ void GraspRrtWindow::loadScene() if (robots.size() != 1) { - VR_ERROR << "Need exactly 1 robot" << endl; + VR_ERROR << "Need exactly 1 robot" << std::endl; return; } @@ -304,7 +304,7 @@ void GraspRrtWindow::loadScene() if (configs.size() < 1) { - VR_ERROR << "Need at least 1 Robot Configurations" << endl; + VR_ERROR << "Need at least 1 Robot Configurations" << std::endl; return; } @@ -325,7 +325,7 @@ void GraspRrtWindow::loadScene() if (obstacles.size() < 1) { - VR_ERROR << "Need at least 1 Obstacle (target object)" << endl; + VR_ERROR << "Need at least 1 Obstacle (target object)" << std::endl; return; } @@ -358,7 +358,7 @@ void GraspRrtWindow::loadScene() //setup eefs if (!robot->hasEndEffector(planSetA.eef)) { - VR_ERROR << "EEF with name " << planSetA.eef << " not known?!" << endl; + VR_ERROR << "EEF with name " << planSetA.eef << " not known?!" << std::endl; return; } @@ -412,7 +412,7 @@ void GraspRrtWindow::selectStart(const std::string& conf) } } - VR_ERROR << "No configuration with name <" << conf << "> found..." << endl; + VR_ERROR << "No configuration with name <" << conf << "> found..." << std::endl; } void GraspRrtWindow::selectTargetObject(const std::string& conf) @@ -427,7 +427,7 @@ void GraspRrtWindow::selectTargetObject(const std::string& conf) } } - VR_ERROR << "No obstacle with name <" << conf << "> found..." << endl; + VR_ERROR << "No obstacle with name <" << conf << "> found..." << std::endl; } void GraspRrtWindow::selectRNS(const std::string& rns) @@ -449,7 +449,7 @@ void GraspRrtWindow::selectRNS(const std::string& rns) } } - VR_ERROR << "No rns with name <" << rns << "> found..." << endl; + VR_ERROR << "No rns with name <" << rns << "> found..." << std::endl; } void GraspRrtWindow::selectEEF(const std::string& eefName) @@ -473,7 +473,7 @@ void GraspRrtWindow::selectEEF(const std::string& eefName) } else { - VR_ERROR << "No eef with name <" << eefName << "> found..." << endl; + VR_ERROR << "No eef with name <" << eefName << "> found..." << std::endl; return; } @@ -487,7 +487,7 @@ void GraspRrtWindow::selectEEF(const std::string& eefName) return; } } - VR_ERROR << "No eef with name <" << eefName << "> found..." << endl;*/ + VR_ERROR << "No eef with name <" << eefName << "> found..." << std::endl;*/ } void GraspRrtWindow::selectColModelRobA(const std::string& colModel) @@ -509,7 +509,7 @@ void GraspRrtWindow::selectColModelRobA(const std::string& colModel) } } - VR_ERROR << "No col model set with name <" << colModel << "> found..." << endl; + VR_ERROR << "No col model set with name <" << colModel << "> found..." << std::endl; } void GraspRrtWindow::selectColModelRobB(const std::string& colModel) { @@ -530,7 +530,7 @@ void GraspRrtWindow::selectColModelRobB(const std::string& colModel) } } - VR_ERROR << "No col model set with name <" << colModel << "> found..." << endl; + VR_ERROR << "No col model set with name <" << colModel << "> found..." << std::endl; } void GraspRrtWindow::selectColModelEnv(const std::string& colModel) { @@ -551,7 +551,7 @@ void GraspRrtWindow::selectColModelEnv(const std::string& colModel) } } - VR_ERROR << "No scene object set with name <" << colModel << "> found..." << endl; + VR_ERROR << "No scene object set with name <" << colModel << "> found..." << std::endl; } void GraspRrtWindow::selectStart(int nr) @@ -802,15 +802,15 @@ void GraspRrtWindow::testGraspPose() p1(0,3) = 50; p2(0,3) = 200; Eigen::Matrix4f deltaPose = p1.inverse() * p2; - cout << deltaPose << endl; + std::cout << deltaPose << std::endl; deltaPose = p2 * p1.inverse(); - cout << deltaPose << endl; + std::cout << deltaPose << std::endl; p2 = deltaPose * p1; - cout << p2 << endl; + std::cout << p2 << std::endl; p2 = p1 * deltaPose; - cout << p2 << endl;*/ + std::cout << p2 << std::endl;*/ } void GraspRrtWindow::plan() @@ -855,7 +855,7 @@ void GraspRrtWindow::plan() if (planOK) { - VR_INFO << " Planning succeeded " << endl; + VR_INFO << " Planning succeeded " << std::endl; solution = graspRrt->getSolution(); Saba::ShortcutProcessorPtr postProcessing(new Saba::ShortcutProcessor(solution, cspace, false)); solutionOptimized = postProcessing->optimize(100); @@ -866,14 +866,14 @@ void GraspRrtWindow::plan() for (size_t i = 0; i < vStoreGraspInfo.size(); i++) { - cout << "processing grasp " << i << endl; + std::cout << "processing grasp " << i << std::endl; VirtualRobot::GraspPtr g(new VirtualRobot::Grasp("GraspRrt Grasp", robot->getType(), eef->getName(), vStoreGraspInfo[i].handToObjectTransform, "GraspRrt", vStoreGraspInfo[i].graspScore)); grasps.push_back(g); } } else { - VR_INFO << " Planning failed" << endl; + VR_INFO << " Planning failed" << std::endl; } sliderSolution(1000); diff --git a/MotionPlanning/examples/IKRRT/IKRRTDemo.cpp b/MotionPlanning/examples/IKRRT/IKRRTDemo.cpp index c241479d676e17ccdadadfe5836664233400306a..61dddb351c3927adc2b39eeda2797bc4f79e7101 100644 --- a/MotionPlanning/examples/IKRRT/IKRRTDemo.cpp +++ b/MotionPlanning/examples/IKRRT/IKRRTDemo.cpp @@ -29,7 +29,7 @@ using namespace VirtualRobot; int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "IK-RRT Demo"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; #ifdef ARMAR std::string filenameScene("scenes/examples/IKRRT/planningHotSpot.xml"); @@ -102,11 +102,11 @@ int main(int argc, char* argv[]) } - cout << "Using scene at " << filenameScene << endl; - cout << "Using reachability at " << filenameReach << endl; - cout << "Using end effector " << eef << endl; - cout << "Using col model (kin chain) " << colModel << endl; - cout << "Using col model (static robot)" << colModelRob << endl; + std::cout << "Using scene at " << filenameScene << std::endl; + std::cout << "Using reachability at " << filenameReach << std::endl; + std::cout << "Using end effector " << eef << std::endl; + std::cout << "Using col model (kin chain) " << colModel << std::endl; + std::cout << "Using col model (static robot)" << colModelRob << std::endl; IKRRTWindow rw(filenameScene, filenameReach, kinChain, eef, colModel, colModelRob); diff --git a/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp b/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp index f58e9958819412623a0f122f1ddbb528257b09ee..2975e9b29c4ba5ad6934c5d9201c6014c68c43c3 100644 --- a/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp +++ b/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp @@ -40,7 +40,7 @@ float TIMER_MS = 30.0f; IKRRTWindow::IKRRTWindow(std::string& sceneFile, std::string& reachFile, std::string& rns, std::string& eef, std::string& colModel, std::string& colModelRob) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; this->sceneFile = sceneFile; this->reachFile = reachFile; @@ -129,7 +129,7 @@ void IKRRTWindow::timerCB(void* data, SoSensor* /*sensor*/) { ikWindow->sliderSolution(1000); ikWindow->closeEEF(); - cout << "Stopping playback" << endl; + std::cout << "Stopping playback" << std::endl; ikWindow->playbackMode = false; } else @@ -265,11 +265,11 @@ void IKRRTWindow::saveScreenshot() if (bRes) { - cout << "wrote image " << counter << endl; + std::cout << "wrote image " << counter << std::endl; } else { - cout << "failed writing image " << counter << endl; + std::cout << "failed writing image " << counter << std::endl; } } @@ -355,7 +355,7 @@ void IKRRTWindow::loadScene() if (!scene) { - VR_ERROR << " no scene ..." << endl; + VR_ERROR << " no scene ..." << std::endl; return; } @@ -363,7 +363,7 @@ void IKRRTWindow::loadScene() if (robots.size() != 1) { - VR_ERROR << "Need exactly 1 robot" << endl; + VR_ERROR << "Need exactly 1 robot" << std::endl; return; } @@ -374,12 +374,12 @@ void IKRRTWindow::loadScene() if (objects.size() < 1) { - VR_ERROR << "Need at least 1 object" << endl; + VR_ERROR << "Need at least 1 object" << std::endl; return; } object = objects[0]; - VR_INFO << "using first manipulation object: " << object->getName() << endl; + VR_INFO << "using first manipulation object: " << object->getName() << std::endl; obstacles = scene->getObstacles(); @@ -390,7 +390,7 @@ void IKRRTWindow::loadScene() if (!eef) { - VR_ERROR << "Need a correct EEF in robot" << endl; + VR_ERROR << "Need a correct EEF in robot" << std::endl; return; } @@ -400,7 +400,7 @@ void IKRRTWindow::loadScene() if (!rns) { - VR_ERROR << "Need a correct RNS in robot" << endl; + VR_ERROR << "Need a correct RNS in robot" << std::endl; } } @@ -443,15 +443,15 @@ void IKRRTWindow::updateObject(float x[6]) { if (object) { - //cout << "getGlobalPose robot:" << endl << robotEEF->getGlobalPose() << endl; - //cout << "getGlobalPose TCP:" << endl << robotEEF_EEF->getTcp()->getGlobalPose() << endl; + //cout << "getGlobalPose robot:" << endl << robotEEF->getGlobalPose() << std::endl; + //cout << "getGlobalPose TCP:" << endl << robotEEF_EEF->getTcp()->getGlobalPose() << std::endl; Eigen::Matrix4f m; MathTools::posrpy2eigen4f(x, m); m = object->getGlobalPose() * m; object->setGlobalPose(m); - cout << "object " << endl; - cout << m << endl; + std::cout << "object " << std::endl; + std::cout << m << std::endl; } @@ -625,7 +625,7 @@ void IKRRTWindow::loadReach() return; } - cout << "Loading Reachability from " << reachFile << endl; + std::cout << "Loading Reachability from " << reachFile << std::endl; reachSpace.reset(new Reachability(robot)); try @@ -634,8 +634,8 @@ void IKRRTWindow::loadReach() } catch (VirtualRobotException& e) { - cout << " ERROR while loading reach space" << endl; - cout << e.what(); + std::cout << " ERROR while loading reach space" << std::endl; + std::cout << e.what(); reachSpace.reset(); return; } @@ -700,7 +700,7 @@ void IKRRTWindow::planIKRRT() if (planOK) { - VR_INFO << " Planning succeeded " << endl; + VR_INFO << " Planning succeeded " << std::endl; solution = ikRrt->getSolution(); Saba::ShortcutProcessorPtr postProcessing(new Saba::ShortcutProcessor(solution, cspace, false)); solutionOptimized = postProcessing->optimize(100); @@ -710,7 +710,7 @@ void IKRRTWindow::planIKRRT() } else { - VR_INFO << " Planning failed" << endl; + VR_INFO << " Planning failed" << std::endl; } sliderSolution(1000); @@ -725,7 +725,7 @@ void IKRRTWindow::colModel() if (reachSpace && graspSet && object) { Eigen::Matrix4f m = reachSpace->sampleReachablePose(); - cout << "getEntry: " << (int)reachSpace->getEntry(m) << endl; + std::cout << "getEntry: " << (int)reachSpace->getEntry(m) << std::endl; /*SoSeparator* sep1 = new SoSeparator; SoSeparator *cs = CoinVisualizationFactory::CreateCoordSystemVisualization(); SoMatrixTransform *mt = new SoMatrixTransform; @@ -774,11 +774,11 @@ void IKRRTWindow::searchIK() if (grasp) { - VR_INFO << "IK successful..." << endl; + VR_INFO << "IK successful..." << std::endl; } else { - VR_INFO << "IK failed..." << endl; + VR_INFO << "IK failed..." << std::endl; } redraw(); diff --git a/MotionPlanning/examples/MultiThreadedPlanning/MTPlanning.cpp b/MotionPlanning/examples/MultiThreadedPlanning/MTPlanning.cpp index 91d19587377786ff07fd734a212182db2be964c1..94cba38287569858ace0513cb9937bda8c03fb51 100644 --- a/MotionPlanning/examples/MultiThreadedPlanning/MTPlanning.cpp +++ b/MotionPlanning/examples/MultiThreadedPlanning/MTPlanning.cpp @@ -19,16 +19,16 @@ int main(int argc, char** argv) { SoDB::init(); SoQt::init(argc, argv, "MT"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; if (!CollisionChecker::IsSupported_Multithreading_MultipleColCheckers()) { - cout << " The collision detection library that is linked to simox does not support multi threading. Aborting...." << endl; + std::cout << " The collision detection library that is linked to simox does not support multi threading. Aborting...." << std::endl; return -1; } #ifdef WIN32 - cout << "Visual Studio users: Be sure to start this example with <ctrl>+F5 (RELEASE mode) for full performance (otherwise only 1 thread will be used)" << endl; + std::cout << "Visual Studio users: Be sure to start this example with <ctrl>+F5 (RELEASE mode) for full performance (otherwise only 1 thread will be used)" << std::endl; #endif try @@ -44,7 +44,7 @@ int main(int argc, char** argv) ; } - cout << " --- END --- " << endl; + std::cout << " --- END --- " << std::endl; return 0; } diff --git a/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp b/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp index 8ab9aa5906d65da3f034de1f2563c8adb58af49b..2e9cdfb629f61ce00d0549790ce73bca059455c5 100644 --- a/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp +++ b/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp @@ -197,7 +197,7 @@ void MTPlanningScenery::buildScene() sceneSep->addChild(obstSep); int ob = 2000; - cout << "Randomly placing " << ob << " obstacles..." << endl; + std::cout << "Randomly placing " << ob << " obstacles..." << std::endl; for (int i = 0; i < ob; i++) { @@ -261,7 +261,7 @@ void MTPlanningScenery::buildPlanningThread(bool bMultiCollisionCheckers, int id { if (!environmentUnited) { - cout << "Build Environment first!..." << endl; + std::cout << "Build Environment first!..." << std::endl; return; } @@ -270,22 +270,22 @@ void MTPlanningScenery::buildPlanningThread(bool bMultiCollisionCheckers, int id return; } - cout << " Build planning thread "; + std::cout << " Build planning thread "; if (bMultiCollisionCheckers) { - cout << "with own instance of collision checker" << endl; + std::cout << "with own instance of collision checker" << std::endl; } else { - cout << "with collision checker singleton" << endl; + std::cout << "with collision checker singleton" << std::endl; } this->loadRobotMTPlanning(bMultiCollisionCheckers); if (this->robots.empty()) { - cout << "Could not load a robot!..." << endl; + std::cout << "Could not load a robot!..." << std::endl; return; } @@ -293,7 +293,7 @@ void MTPlanningScenery::buildPlanningThread(bool bMultiCollisionCheckers, int id RobotNodeSetPtr kinChain = pRobot->getRobotNodeSet(kinChainName); CDManagerPtr pCcm(new VirtualRobot::CDManager(pRobot->getCollisionChecker())); - cout << "Set CSpace for " << robots.size() << ".th robot." << endl; + std::cout << "Set CSpace for " << robots.size() << ".th robot." << std::endl; pCcm->addCollisionModel(pRobot->getRobotNodeSet(colModel)); ObstaclePtr pEnv = environmentUnited; @@ -329,7 +329,7 @@ void MTPlanningScenery::buildPlanningThread(bool bMultiCollisionCheckers, int id start[0] = x; start[1] = y; start[2] = z; - cout << "START: " << x << "," << y << "," << z << endl; + std::cout << "START: " << x << "," << y << "," << z << std::endl; pRobot->setJointValues(kinChain, start); } while (pCcm->isInCollision()); @@ -342,7 +342,7 @@ void MTPlanningScenery::buildPlanningThread(bool bMultiCollisionCheckers, int id goal[0] = x; goal[1] = y; goal[2] = z; - cout << "GOAL: " << x << "," << y << "," << z << endl; + std::cout << "GOAL: " << x << "," << y << "," << z << std::endl; pRobot->setJointValues(kinChain, goal); } while (pCcm->isInCollision()); @@ -449,7 +449,7 @@ PathProcessingThreadPtr MTPlanningScenery::buildOptimizeThread(CSpaceSampledPtr void MTPlanningScenery::stopPlanning() { - cout << "Stopping " << planningThreads.size() << " planning threads..." << endl; + std::cout << "Stopping " << planningThreads.size() << " planning threads..." << std::endl; for (auto & planningThread : planningThreads) { @@ -461,7 +461,7 @@ void MTPlanningScenery::stopPlanning() robot->setUpdateVisualization(true); } - cout << "... done" << endl; + std::cout << "... done" << std::endl; plannersStarted = false; } @@ -470,11 +470,11 @@ void MTPlanningScenery::stopOptimizing() { if (!optimizeStarted) { - cout << "Start the optimizing first!..." << endl; + std::cout << "Start the optimizing first!..." << std::endl; return; } - cout << "Stopping " << optimizeThreads.size() << " optimizing threads..." << endl; + std::cout << "Stopping " << optimizeThreads.size() << " optimizing threads..." << std::endl; for (auto & optimizeThread : optimizeThreads) { @@ -486,7 +486,7 @@ void MTPlanningScenery::stopOptimizing() robot->setUpdateVisualization(true); } - cout << "...done" << endl; + std::cout << "...done" << std::endl; optimizeStarted = false; } @@ -495,11 +495,11 @@ void MTPlanningScenery::startPlanning() { if (plannersStarted) { - cout << "already started!..." << endl; + std::cout << "already started!..." << std::endl; return; } - cout << "Starting " << planningThreads.size() << " planning threads..." << endl; + std::cout << "Starting " << planningThreads.size() << " planning threads..." << std::endl; for (auto & robot : robots) { @@ -511,7 +511,7 @@ void MTPlanningScenery::startPlanning() planningThread->start(); } - cout << "... done" << endl; + std::cout << "... done" << std::endl; // give thread some time to startup //boost::this_thread::sleep(boost::posix_time::milliseconds(750)); @@ -525,13 +525,13 @@ void MTPlanningScenery::startOptimizing() { if (!plannersStarted) { - cout << "Plan the solutions first!..." << endl; + std::cout << "Plan the solutions first!..." << std::endl; return; } if (CSpaces.empty() || solutions.empty()) { - cout << "Build planning threads first!..." << endl; + std::cout << "Build planning threads first!..." << std::endl; return; } @@ -541,7 +541,7 @@ void MTPlanningScenery::startOptimizing() { if (planningThread->isRunning()) { - cout << "Planning is not finish!..." << endl; + std::cout << "Planning is not finish!..." << std::endl; return; } } @@ -549,7 +549,7 @@ void MTPlanningScenery::startOptimizing() if (optimizeStarted) { - cout << "Path processors already started..." << endl; + std::cout << "Path processors already started..." << std::endl; return; } @@ -578,8 +578,8 @@ void MTPlanningScenery::startOptimizing() } } - cout << "... done" << endl; - cout << "Starting " << j << " path processing threads..." << endl; + std::cout << "... done" << std::endl; + std::cout << "Starting " << j << " path processing threads..." << std::endl; optimizeStarted = true; } @@ -602,7 +602,7 @@ void MTPlanningScenery::loadRobotMTPlanning(bool bMultiCollisionCheckers) if (!pRobot) { - cout << "Error parsing file " << robotFilename << ". Aborting" << endl; + std::cout << "Error parsing file " << robotFilename << ". Aborting" << std::endl; return; } @@ -610,12 +610,12 @@ void MTPlanningScenery::loadRobotMTPlanning(bool bMultiCollisionCheckers) if (!kinChain) { - cout << "No rns " << kinChainName << ". Aborting" << endl; + std::cout << "No rns " << kinChainName << ". Aborting" << std::endl; return; } // get robot - cout << "Successfully read " << robotFilename << std::endl; + std::cout << "Successfully read " << robotFilename << std::endl; } else { @@ -624,7 +624,7 @@ void MTPlanningScenery::loadRobotMTPlanning(bool bMultiCollisionCheckers) if (!pRobot) { - cout << "error while parsing xml file: no pRobot.." << std::endl; + std::cout << "error while parsing xml file: no pRobot.." << std::endl; return; } @@ -654,9 +654,9 @@ void MTPlanningScenery::loadRobotMTPlanning(bool bMultiCollisionCheckers) int trFull = pRobot->getNumFaces(false); int trCol = pRobot->getNumFaces(true); - cout << "Loaded/Cloned robot with " << trFull << "/" << trCol << " number of triangles." << endl; + std::cout << "Loaded/Cloned robot with " << trFull << "/" << trCol << " number of triangles." << std::endl; //reset(); - cout << "Loaded/Cloned " << (int)robots.size() << " robots..." << endl; + std::cout << "Loaded/Cloned " << (int)robots.size() << " robots..." << std::endl; } @@ -794,7 +794,7 @@ void MTPlanningScenery::checkPlanningThreads() if (sol) { solutions[i] = sol->clone(); - cout << "fetching solution " << i << endl; + std::cout << "fetching solution " << i << std::endl; CoinRrtWorkspaceVisualizationPtr visu(new CoinRrtWorkspaceVisualization(robots[i], CSpaces[i], TCPName)); visu->addCSpacePath(solutions[i]); visu->addTree(planners[i]->getTree()); @@ -803,7 +803,7 @@ void MTPlanningScenery::checkPlanningThreads() } else { - cout << "no solution in thread " << i << endl; + std::cout << "no solution in thread " << i << std::endl; } } } @@ -828,7 +828,7 @@ void MTPlanningScenery::checkOptimizeThreads() { if (!optiSolutions[i]) { - cout << "fetching solution " << i << endl; + std::cout << "fetching solution " << i << std::endl; sceneSep->removeChild(visualisations[i]); optiSolutions[i] = pOptiSol->clone(); CoinRrtWorkspaceVisualizationPtr visu(new CoinRrtWorkspaceVisualization(robots[i], CSpaces[i], TCPName)); @@ -839,8 +839,8 @@ void MTPlanningScenery::checkOptimizeThreads() } else { - cout << "No optimized solution in thread " << i << endl; - cout << "show the original solution" << endl; + std::cout << "No optimized solution in thread " << i << std::endl; + std::cout << "show the original solution" << std::endl; } } } @@ -905,7 +905,7 @@ int MTPlanningScenery::getThreads() //xmlParser.forceBoundingBox(true); if (!xmlParser.parse(robotFilename.c_str())) { - cout << "Error parsing file " << robotFilename << ". Aborting" << endl; + std::cout << "Error parsing file " << robotFilename << ". Aborting" << std::endl; return; } @@ -913,10 +913,10 @@ int MTPlanningScenery::getThreads() robot = xmlParser.GetRobot(); if (robot == NULL) { - cout << "error while parsing xml file: no pRobot.." << std::endl; + std::cout << "error while parsing xml file: no pRobot.." << std::endl; return; } - cout << "Successfully read " << robotFilename << std::endl; + std::cout << "Successfully read " << robotFilename << std::endl; robotSep = new SoSeparator(); robot->GetVisualisationGraph(robotSep, robotModelVisuColModel); @@ -927,7 +927,7 @@ int MTPlanningScenery::getThreads() int trFull = robot->GetNumberOfTriangles(false); int trCol = robot->GetNumberOfTriangles(true); - cout << "Loaded robot with " << trFull << "/" << trCol << " number of triangles." << endl; + std::cout << "Loaded robot with " << trFull << "/" << trCol << " number of triangles." << std::endl; //reset(); } @@ -936,12 +936,12 @@ void MTPlanningScenery::plan(int index) { if(robot == NULL) { - cout << "Load a robot first!..." << endl; + std::cout << "Load a robot first!..." << std::endl; return; } if(environment == NULL) { - cout << "Create the Environment first!..." << endl; + std::cout << "Create the Environment first!..." << std::endl; return; } @@ -1002,7 +1002,7 @@ void MTPlanningScenery::plan(int index) bool res = pBiPlanner->Plan(); if(res) { - cout << "successfully!..." << endl; + std::cout << "successfully!..." << std::endl; solutionsForSeq.push_back(pBiPlanner->GetSolution()); visualizationsForSeq.push_back(NULL); showSolution(solutionsForSeq[g_iSolutionIndex], g_iSolutionIndex); @@ -1010,7 +1010,7 @@ void MTPlanningScenery::plan(int index) } else { - cout << "MTPlanningScenery::plan::Plan failed..." << endl; + std::cout << "MTPlanningScenery::plan::Plan failed..." << std::endl; } g_iSolutionIndex++; } @@ -1020,7 +1020,7 @@ void MTPlanningScenery::optimizeSolution(int solutionIndex) { if((CSpace1 == NULL) || (solutionsForSeq[solutionIndex] == NULL)) { - cout << "MTPlanningScenery::optimizeSolution::Plan a solution first!..." << endl; + std::cout << "MTPlanningScenery::optimizeSolution::Plan a solution first!..." << std::endl; return; } @@ -1031,12 +1031,12 @@ void MTPlanningScenery::optimizeSolution(int solutionIndex) { showSolution(optiSolutionsForSeq[solutionIndex], solutionIndex); int iEndSize = optiSolutionsForSeq[solutionIndex]->GetPathSize(); - cout << "MTPlanningScenery::optimizeSolution::New Size: " << iEndSize << " Nodes." << endl; - cout << "MTPlanningScenery::optimizeSolution::Kicked " << (iBeforeSize - iEndSize) << " Nodes." << endl; + std::cout << "MTPlanningScenery::optimizeSolution::New Size: " << iEndSize << " Nodes." << std::endl; + std::cout << "MTPlanningScenery::optimizeSolution::Kicked " << (iBeforeSize - iEndSize) << " Nodes." << std::endl; } else { - cout << "MTPlanningScenery::optimizeSolution::Optimize failed..." << endl; + std::cout << "MTPlanningScenery::optimizeSolution::Optimize failed..." << std::endl; } } @@ -1044,7 +1044,7 @@ void MTPlanningScenery::showSolution(CRrtSolution *solToShow, int solutionIndex) { if(solToShow == NULL) { - cout << "MTPlanningScenery::showSolution::No solution!..." << endl; + std::cout << "MTPlanningScenery::showSolution::No solution!..." << std::endl; return; } diff --git a/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningWindow.cpp b/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningWindow.cpp index 5b855cc67211b6792ec02e4b38e0787e300b4c2d..92f6b4916fd2301a6d4da1da1959ba1c682e8d66 100644 --- a/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningWindow.cpp +++ b/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningWindow.cpp @@ -85,7 +85,7 @@ void MTPlanningWindow::timerCBPlanning(void* data, SoSensor* /*sensor*/) double runtime = (double)(mtWindow->endTime - mtWindow->startTime) / CLOCKS_PER_SEC; sText = "Runtime: " + QString::number(runtime) + "s"; mtWindow->UI.labelRuntime->setText(sText); - cout << "Runtime = " << runtime << endl; + std::cout << "Runtime = " << runtime << std::endl; runtimeDisplayed = true; } } @@ -108,10 +108,10 @@ void MTPlanningWindow::timerCBOptimize(void* data, SoSensor* /*sensor*/) { mtWindow->optiEndTime = clock(); double runtime = (double)(mtWindow->optiEndTime - mtWindow->optiStartTime) / CLOCKS_PER_SEC; - cout << "Runtime:" << runtime << endl; + std::cout << "Runtime:" << runtime << std::endl; sText = "Optimizing Time: " + QString::number(runtime) + "s"; mtWindow->UI.labelOptiTime->setText(sText); - cout << "Optimizing Time = " << runtime << endl; + std::cout << "Optimizing Time = " << runtime << std::endl; optiTimeDisplayed = true; } } @@ -256,8 +256,8 @@ void MTPlanningWindow::stopOptimize() QString sText; sText = "Plan Time: " + QString::number(runtime) + "s"; sQRuntimeLabel->setText(sText); - cout << "The total plantime is " << runtime << " ." << endl; - cout << "The number of the plannings is " << i << " ." << endl; + std::cout << "The total plantime is " << runtime << " ." << std::endl; + std::cout << "The number of the plannings is " << i << " ." << std::endl; } void MTPlanningWindow::optimizeSolution() @@ -274,6 +274,6 @@ void MTPlanningWindow::optimizeSolution() QString sText; sText = "optimizing Time: " + QString::number(runtime) + "s"; sQOptimizeTimeLabel->setText(sText); - cout << "The total optimization time is " << runtime << " ." << endl; - cout << "The number of the optimizations is " << i << " ." << endl; + std::cout << "The total optimization time is " << runtime << " ." << std::endl; + std::cout << "The number of the optimizations is " << i << " ." << std::endl; }*/ diff --git a/MotionPlanning/examples/PlatformDemo/PlatformDemo.cpp b/MotionPlanning/examples/PlatformDemo/PlatformDemo.cpp index c3a6a74fe040ed2319654157f2ee6ba0281862be..f3a33a0b2fbd57f90fba882c7bd8c55c4cbdd5d5 100644 --- a/MotionPlanning/examples/PlatformDemo/PlatformDemo.cpp +++ b/MotionPlanning/examples/PlatformDemo/PlatformDemo.cpp @@ -28,7 +28,7 @@ int main(int argc, char** argv) { VirtualRobot::init(argc, argv, "GraspRrtDemo"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; std::string filenameScene("/scenes/examples/PlatformDemo/PlatformDemo.xml"); VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(filenameScene); @@ -73,10 +73,10 @@ int main(int argc, char** argv) } - cout << "Using scene: " << filenameScene << endl; - cout << "Using environment collision model set: <" << colModel2 << ">" << endl; - cout << "\t Using RobotNodeSet for planning: <" << rnsName << ">" << endl; - cout << "\t Using robot collision model set: <" << colModel1 << ">" << endl; + std::cout << "Using scene: " << filenameScene << std::endl; + std::cout << "Using environment collision model set: <" << colModel2 << ">" << std::endl; + std::cout << "\t Using RobotNodeSet for planning: <" << rnsName << ">" << std::endl; + std::cout << "\t Using robot collision model set: <" << colModel1 << ">" << std::endl; PlatformWindow rw(filenameScene, rnsName, colModel1, colModel2); diff --git a/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp b/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp index 5e11018841258361ed1bd949231dfcd36391e91a..7fc3a40a556f8cbaf385377a00fe6bcb91c7a99c 100644 --- a/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp +++ b/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp @@ -45,7 +45,7 @@ PlatformWindow::PlatformWindow(const std::string& sceneFile, const std::string& colModelEnv) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; this->sceneFile = sceneFile; @@ -208,7 +208,7 @@ void PlatformWindow::loadScene() if (!scene) { - VR_ERROR << " no scene ..." << endl; + VR_ERROR << " no scene ..." << std::endl; return; } @@ -216,7 +216,7 @@ void PlatformWindow::loadScene() if (robots.size() != 1) { - VR_ERROR << "Need exactly 1 robot" << endl; + VR_ERROR << "Need exactly 1 robot" << std::endl; return; } @@ -227,7 +227,7 @@ void PlatformWindow::loadScene() if (obstacles.size() < 1) { - VR_ERROR << "Need at least 1 Obstacle (target object)" << endl; + VR_ERROR << "Need at least 1 Obstacle (target object)" << std::endl; return; } @@ -454,7 +454,7 @@ void PlatformWindow::showOptizerForces(Saba::ElasticBandProcessorPtr postProcess void PlatformWindow::optimizeSolution(postProcessingMethod postProcessing, int nrSteps) { - VR_INFO << " Smoothing solution with " << nrSteps << " steps " << endl; + VR_INFO << " Smoothing solution with " << nrSteps << " steps " << std::endl; forcesSep->removeAllChildren(); if (nrSteps<=0) return; @@ -469,7 +469,7 @@ void PlatformWindow::optimizeSolution(postProcessingMethod postProcessing, int n case eElasticBands: { RobotNodePtr n = colModelRob->getNode(0); - VR_INFO << "using elsatic band processor with node " << n->getName() << endl; + VR_INFO << "using elsatic band processor with node " << n->getName() << std::endl; Saba::ElasticBandProcessorPtr postProcessing(new Saba::ElasticBandProcessor(solutionOptimized, cspace, n, colModelEnv, false)); // specific to armar3: Eigen::VectorXf w(3); @@ -481,9 +481,9 @@ void PlatformWindow::optimizeSolution(postProcessingMethod postProcessing, int n break; } default: - VR_INFO << "post processing method nyi" << endl; + VR_INFO << "post processing method nyi" << std::endl; } - VR_INFO << " Smoothing done" << endl; + VR_INFO << " Smoothing done" << std::endl; } void PlatformWindow::plan() @@ -528,7 +528,7 @@ void PlatformWindow::plan() if (planOK) { - VR_INFO << " Planning succeeded " << endl; + VR_INFO << " Planning succeeded " << std::endl; solution = rrt->getSolution(); solutionOptimized = solution->clone(); @@ -544,7 +544,7 @@ void PlatformWindow::plan() } else { - VR_INFO << " Planning failed" << endl; + VR_INFO << " Planning failed" << std::endl; } sliderSolution(1000); diff --git a/MotionPlanning/examples/RRT/RRTdemo.cpp b/MotionPlanning/examples/RRT/RRTdemo.cpp index 08885df145697e9bc8b3d7507bd7e34aed993499..33e942b4fa20965953aae91921e7ad1ccaf4a4d7 100644 --- a/MotionPlanning/examples/RRT/RRTdemo.cpp +++ b/MotionPlanning/examples/RRT/RRTdemo.cpp @@ -74,7 +74,7 @@ void startRRTVisualization() // create robot std::string filename("robots/examples/RrtDemo/Joint3.xml"); VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(filename); - cout << "Loading 3DOF robot from " << filename << endl; + std::cout << "Loading 3DOF robot from " << filename << std::endl; RobotPtr robot = RobotIO::loadRobot(filename); if (!robot) @@ -154,12 +154,12 @@ void startRRTVisualization() } planningTime /= (float)loops; - cout << "Avg planning time: " << planningTime << endl; - cout << "failed:" << failed << endl; + std::cout << "Avg planning time: " << planningTime << std::endl; + std::cout << "failed:" << failed << std::endl; if (!ok) { - cout << "planning failed..." << endl; + std::cout << "planning failed..." << std::endl; return; } @@ -212,7 +212,7 @@ int main(int /*argc*/, char** /*argv*/) { SoDB::init(); win = SoQt::init("RRT Demo", "RRT Demo"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; try { @@ -231,7 +231,7 @@ int main(int /*argc*/, char** /*argv*/) ; } - cout << " --- END --- " << endl; + std::cout << " --- END --- " << std::endl; return 0; } diff --git a/MotionPlanning/examples/RrtGui/RrtGui.cpp b/MotionPlanning/examples/RrtGui/RrtGui.cpp index 45eeb5cd3d0e0be3bd277a00048a1a38ef99ba4e..9439630a336ddba5f41b51e089c393adb8a396ca 100644 --- a/MotionPlanning/examples/RrtGui/RrtGui.cpp +++ b/MotionPlanning/examples/RrtGui/RrtGui.cpp @@ -28,7 +28,7 @@ int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "RRT Demo Gui"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; std::string filenameScene("scenes/examples/RrtGui/planning.xml"); VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(filenameScene); @@ -99,12 +99,12 @@ int main(int argc, char* argv[]) } - cout << "Using scene: " << filenameScene << endl; - cout << "Using start config: " << startConfig << endl; - cout << "Using goal config: " << goalConfig << endl; - cout << "Using RobotNodeSet for planning: " << rnsName << endl; - cout << "Using robot collision model sets: " << colModel1 << " and " << colModel2 << endl; - cout << "Using environment collision model set: " << colModel3 << endl; + std::cout << "Using scene: " << filenameScene << std::endl; + std::cout << "Using start config: " << startConfig << std::endl; + std::cout << "Using goal config: " << goalConfig << std::endl; + std::cout << "Using RobotNodeSet for planning: " << rnsName << std::endl; + std::cout << "Using robot collision model sets: " << colModel1 << " and " << colModel2 << std::endl; + std::cout << "Using environment collision model set: " << colModel3 << std::endl; RrtGuiWindow rw(filenameScene, startConfig, goalConfig, rnsName, colModel1, colModel2, colModel3); diff --git a/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp b/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp index a285fdad90101e139adad8fcbdd85b8f74f5a51a..48fc22773bf5e235c951eb591cc029985c71bd04 100644 --- a/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp +++ b/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp @@ -39,7 +39,7 @@ RrtGuiWindow::RrtGuiWindow(const std::string& sceneFile, const std::string& sCon const std::string& rns, const std::string& colModelRob1, const std::string& colModelRob2, const std::string& colModelEnv) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; this->sceneFile = sceneFile; @@ -267,7 +267,7 @@ void RrtGuiWindow::loadScene() if (!scene) { - VR_ERROR << " no scene ..." << endl; + VR_ERROR << " no scene ..." << std::endl; return; } @@ -276,7 +276,7 @@ void RrtGuiWindow::loadScene() if (robots.size() != 1) { - VR_ERROR << "Need exactly 1 robot" << endl; + VR_ERROR << "Need exactly 1 robot" << std::endl; return; } @@ -287,7 +287,7 @@ void RrtGuiWindow::loadScene() if (configs.size() < 2) { - VR_ERROR << "Need at least 2 Robot Configurations" << endl; + VR_ERROR << "Need at least 2 Robot Configurations" << std::endl; return; } @@ -351,7 +351,7 @@ void RrtGuiWindow::selectStart(const std::string& conf) } } - VR_ERROR << "No configuration with name <" << conf << "> found..." << endl; + VR_ERROR << "No configuration with name <" << conf << "> found..." << std::endl; } void RrtGuiWindow::selectGoal(const std::string& conf) { @@ -365,7 +365,7 @@ void RrtGuiWindow::selectGoal(const std::string& conf) } } - VR_ERROR << "No configuration with name <" << conf << "> found..." << endl; + VR_ERROR << "No configuration with name <" << conf << "> found..." << std::endl; } void RrtGuiWindow::selectRNS(const std::string& rns) @@ -387,7 +387,7 @@ void RrtGuiWindow::selectRNS(const std::string& rns) } } - VR_ERROR << "No rns with name <" << rns << "> found..." << endl; + VR_ERROR << "No rns with name <" << rns << "> found..." << std::endl; } void RrtGuiWindow::selectColModelRobA(const std::string& colModel) @@ -409,7 +409,7 @@ void RrtGuiWindow::selectColModelRobA(const std::string& colModel) } } - VR_ERROR << "No col model set with name <" << colModel << "> found..." << endl; + VR_ERROR << "No col model set with name <" << colModel << "> found..." << std::endl; } void RrtGuiWindow::selectColModelRobB(const std::string& colModel) { @@ -430,7 +430,7 @@ void RrtGuiWindow::selectColModelRobB(const std::string& colModel) } } - VR_ERROR << "No col model set with name <" << colModel << "> found..." << endl; + VR_ERROR << "No col model set with name <" << colModel << "> found..." << std::endl; } void RrtGuiWindow::selectColModelEnv(const std::string& colModel) { @@ -451,7 +451,7 @@ void RrtGuiWindow::selectColModelEnv(const std::string& colModel) } } - VR_ERROR << "No scene object set with name <" << colModel << "> found..." << endl; + VR_ERROR << "No scene object set with name <" << colModel << "> found..." << std::endl; } void RrtGuiWindow::selectStart(int nr) @@ -697,7 +697,7 @@ void RrtGuiWindow::plan() if (planOK) { - VR_INFO << " Planning succeeded " << endl; + VR_INFO << " Planning succeeded " << std::endl; solution = mp->getSolution(); Saba::ShortcutProcessorPtr postProcessing(new Saba::ShortcutProcessor(solution, cspace, false)); solutionOptimized = postProcessing->optimize(100); @@ -715,7 +715,7 @@ void RrtGuiWindow::plan() } else { - VR_INFO << " Planning failed" << endl; + VR_INFO << " Planning failed" << std::endl; } sliderSolution(1000); diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.cpp index c8b14a4a0373709648d3e8aaf0bde50d17aa89e3..cb13e56c7331bc175d6eed06bd0fe6fdb03f4ef7 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.cpp @@ -73,7 +73,7 @@ namespace SimDynamics BulletCoinQtViewer* bulletViewer = static_cast<BulletCoinQtViewer*>(userdata); VR_ASSERT(bulletViewer); - VR_INFO << "Selected object" << endl; + VR_INFO << "Selected object" << std::endl; bulletViewer->customSelection(path); @@ -84,7 +84,7 @@ namespace SimDynamics BulletCoinQtViewer* bulletViewer = static_cast<BulletCoinQtViewer*>(userdata); VR_ASSERT(bulletViewer); - VR_INFO << "Deselected object" << endl; + VR_INFO << "Deselected object" << std::endl; bulletViewer->customDeselection(path); @@ -183,7 +183,7 @@ namespace SimDynamics // Commented out: This is now handled by Bullet (bulletMaxSubSteps * bulletTimeStepMsec is the maximal duration of a frame) /* double minFPS = 1000000.f/40.f; // Don't use 60 Hz (cannot be reached due to Vsync) if (ms > minFPS) { - VR_INFO << "Slow frame (" << ms << "us elapsed)! Limiting elapsed time (losing realtime capabilities for this frame)." << endl; + VR_INFO << "Slow frame (" << ms << "us elapsed)! Limiting elapsed time (losing realtime capabilities for this frame)." << std::endl; ms = minFPS; } */ if (!simModeFixedTimeStep) @@ -192,7 +192,7 @@ namespace SimDynamics { if (!warned_norealtime) { - VR_INFO << "Elapsed time (" << (ms / 1000.0f) << "ms) too long: Simulation is not running in realtime." << endl; + VR_INFO << "Elapsed time (" << (ms / 1000.0f) << "ms) too long: Simulation is not running in realtime." << std::endl; warned_norealtime = true; } } @@ -215,7 +215,7 @@ namespace SimDynamics } } - // VR_INFO << "stepSimulation(" << dt1 << ", " << bulletMaxSubSteps << ", " << (bulletTimeStepMsec / 1000.0f) << ")" << endl; + // VR_INFO << "stepSimulation(" << dt1 << ", " << bulletMaxSubSteps << ", " << (bulletTimeStepMsec / 1000.0f) << ")" << std::endl; //optional but useful: debug drawing //m_dynamicsWorld->debugDrawWorld(); diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.h b/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.h index f7d28e379f7f6161d1b29e9cdbdc1a97f66e3e97..f550391e1a060f52cbcefeb5ba4d086cf4e5f857 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.h +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletCoinQtViewer.h @@ -208,12 +208,12 @@ namespace SimDynamics */ virtual void customSelection(SoPath* path) { - std::cout << "Selecting node " << path->getTail()->getTypeId().getName().getString() << endl; + std::cout << "Selecting node " << path->getTail()->getTypeId().getName().getString() << std::endl; } virtual void customDeselection(SoPath* path) { - std::cout << "Deselecting node " << path->getTail()->getTypeId().getName().getString() << endl; + std::cout << "Deselecting node " << path->getTail()->getTypeId().getName().getString() << std::endl; } //! Redraw diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp index 586eb94c1be8b3339e6b9ef716f91f18100513f7..530522e77ef53374d8b175ad3dbdf01d9baa76d8 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp @@ -188,7 +188,7 @@ namespace SimDynamics if (!btObject) { - VR_ERROR << "Skipping non-BULLET object " << (*i)->getName() << "!" << endl; + VR_ERROR << "Skipping non-BULLET object " << (*i)->getName() << "!" << std::endl; continue; } auto friction = btObject->getSceneObject()->getPhysics().friction; @@ -209,7 +209,7 @@ namespace SimDynamics if (!btObject) { - VR_ERROR << "Could only handle BULLET objects?! <" << o->getName() << ">" << endl; + VR_ERROR << "Could only handle BULLET objects?! <" << o->getName() << ">" << std::endl; return false; } @@ -261,7 +261,7 @@ namespace SimDynamics if (!btObject) { - VR_ERROR << "Could only handle BULLET objects?! <" << o->getName() << ">" << endl; + VR_ERROR << "Could only handle BULLET objects?! <" << o->getName() << ">" << std::endl; return false; } @@ -440,7 +440,7 @@ namespace SimDynamics if (!btRobot) { - VR_ERROR << "Could only handle BULLET objects?! <" << r->getName() << ">" << endl; + VR_ERROR << "Could only handle BULLET objects?! <" << r->getName() << ">" << std::endl; return false; } @@ -504,7 +504,7 @@ namespace SimDynamics if (!btRobot) { - VR_ERROR << "Could only handle BULLET objects?! <" << r->getName() << ">" << endl; + VR_ERROR << "Could only handle BULLET objects?! <" << r->getName() << ">" << std::endl; return false; } @@ -529,7 +529,7 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); #ifdef DEBUG_FIXED_OBJECTS - cout << "TEST2" << endl; + std::cout << "TEST2" << std::endl; #else dynamicsWorld->addConstraint(l.joint.get(), true); #endif @@ -545,47 +545,47 @@ namespace SimDynamics void BulletEngine::print() { MutexLockPtr lock = getScopedLock(); - cout << "------------------ Bullet Engine ------------------" << endl; + std::cout << "------------------ Bullet Engine ------------------" << std::endl; for (size_t i = 0; i < objects.size(); i++) { - cout << "++ Object " << i << ":" << objects[i]->getName() << endl; + std::cout << "++ Object " << i << ":" << objects[i]->getName() << std::endl; Eigen::Matrix4f m = objects[i]->getSceneObject()->getGlobalPose(); - cout << " pos (simox) " << m(0, 3) << "," << m(1, 3) << "," << m(2, 3) << endl; + std::cout << " pos (simox) " << m(0, 3) << "," << m(1, 3) << "," << m(2, 3) << std::endl; BulletObjectPtr bo = std::dynamic_pointer_cast<BulletObject>(objects[i]); std::shared_ptr<btRigidBody> rb = bo->getRigidBody(); btVector3 v = rb->getWorldTransform().getOrigin(); - cout << " pos (bullet) " << v[0] << "," << v[1] << "," << v[2] << endl; + std::cout << " pos (bullet) " << v[0] << "," << v[1] << "," << v[2] << std::endl; btVector3 va = rb->getAngularVelocity(); btVector3 vl = rb->getLinearVelocity(); - cout << " ang vel (bullet) " << va[0] << "," << va[1] << "," << va[2] << endl; - cout << " lin vel (bullet) " << vl[0] << "," << vl[1] << "," << vl[2] << endl; + std::cout << " ang vel (bullet) " << va[0] << "," << va[1] << "," << va[2] << std::endl; + std::cout << " lin vel (bullet) " << vl[0] << "," << vl[1] << "," << vl[2] << std::endl; } for (size_t i = 0; i < robots.size(); i++) { - cout << "++ Robot " << i << ":" << objects[i]->getName() << endl; + std::cout << "++ Robot " << i << ":" << objects[i]->getName() << std::endl; BulletRobotPtr br = std::dynamic_pointer_cast<BulletRobot>(robots[i]); std::vector<BulletRobot::LinkInfo> links = br->getLinks(); for (size_t j = 0; j < links.size(); j++) { - cout << "++++ Link " << j << ":" << links[j].nodeJoint->getName(); - cout << "++++ - ColModelA " << j << ":" << links[j].nodeA->getName(); - cout << "++++ - ColModelB " << j << ":" << links[j].nodeB->getName(); + std::cout << "++++ Link " << j << ":" << links[j].nodeJoint->getName(); + std::cout << "++++ - ColModelA " << j << ":" << links[j].nodeA->getName(); + std::cout << "++++ - ColModelB " << j << ":" << links[j].nodeB->getName(); - cout << " enabled:" << links[j].joint->isEnabled() << endl; + std::cout << " enabled:" << links[j].joint->isEnabled() << std::endl; std::shared_ptr<btHingeConstraint> hinge = std::dynamic_pointer_cast<btHingeConstraint>(links[j].joint); if (hinge) { - cout << " hinge motor enabled:" << hinge->getEnableAngularMotor() << endl; - cout << " hinge angle :" << hinge->getHingeAngle() << endl; - cout << " hinge max motor impulse :" << hinge->getMaxMotorImpulse() << endl; + std::cout << " hinge motor enabled:" << hinge->getEnableAngularMotor() << std::endl; + std::cout << " hinge angle :" << hinge->getHingeAngle() << std::endl; + std::cout << " hinge max motor impulse :" << hinge->getMaxMotorImpulse() << std::endl; #ifdef SIMOX_USES_OLD_BULLET - cout << " hinge motor target vel :" << hinge->getMotorTargetVelosity() << endl; + std::cout << " hinge motor target vel :" << hinge->getMotorTargetVelosity() << std::endl; #else - cout << " hinge motor target vel :" << hinge->getMotorTargetVelocity() << endl; + std::cout << " hinge motor target vel :" << hinge->getMotorTargetVelocity() << std::endl; #endif } @@ -595,17 +595,17 @@ namespace SimDynamics { btRotationalLimitMotor* m = dof->getRotationalLimitMotor(2); VR_ASSERT(m); - cout << " generic_6DOF_joint: axis 5 (z)" << endl; - cout << " generic_6DOF_joint motor enabled:" << m->m_enableMotor << endl; - cout << " generic_6DOF_joint angle :" << m->m_currentPosition << endl; - cout << " generic_6DOF_joint max motor force :" << m->m_maxMotorForce << endl; - cout << " higeneric_6DOF_jointnge motor target vel :" << m->m_targetVelocity << endl; + std::cout << " generic_6DOF_joint: axis 5 (z)" << std::endl; + std::cout << " generic_6DOF_joint motor enabled:" << m->m_enableMotor << std::endl; + std::cout << " generic_6DOF_joint angle :" << m->m_currentPosition << std::endl; + std::cout << " generic_6DOF_joint max motor force :" << m->m_maxMotorForce << std::endl; + std::cout << " higeneric_6DOF_jointnge motor target vel :" << m->m_targetVelocity << std::endl; } } } - cout << "------------------ Bullet Engine ------------------" << endl; + std::cout << "------------------ Bullet Engine ------------------" << std::endl; } @@ -692,20 +692,20 @@ namespace SimDynamics if (!br) { - VR_ERROR << "no bullet robot" << endl; + VR_ERROR << "no bullet robot" << std::endl; return false; } if (object->getSimType() != VirtualRobot::SceneObject::Physics::eDynamic) { - VR_WARNING << "Sim type of object " << object->getName() << "!=eDynamic. Is this intended?" << endl; + VR_WARNING << "Sim type of object " << object->getName() << "!=eDynamic. Is this intended?" << std::endl; } BulletRobot::LinkInfoPtr link = br->attachObjectLink(nodeName, object); if (!link) { - VR_ERROR << "Failed to create bullet robot link" << endl; + VR_ERROR << "Failed to create bullet robot link" << std::endl; return false; } @@ -726,7 +726,7 @@ namespace SimDynamics if (!br) { - VR_ERROR << "no bullet robot" << endl; + VR_ERROR << "no bullet robot" << std::endl; return false; } @@ -734,7 +734,7 @@ namespace SimDynamics if (!bo) { - VR_ERROR << "no bullet object" << endl; + VR_ERROR << "no bullet object" << std::endl; return false; } @@ -749,7 +749,7 @@ namespace SimDynamics if (!res) { - VR_ERROR << "Failed to detach object" << endl; + VR_ERROR << "Failed to detach object" << std::endl; return false; } @@ -772,7 +772,7 @@ void SimDynamics::BulletEngine::updateAction(btCollisionWorld* /*collisionWorld* callback.first(callback.second, deltaTimeStep); } std::chrono::duration<double> diff = (std::chrono::system_clock::now() - start); - // cout << "duration: " << diff.count() << endl; + // std::cout << "duration: " << diff.count() << std::endl; } void SimDynamics::BulletEngine::debugDraw(btIDebugDraw* /*debugDrawer*/) diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.cpp index 30d76079707d844c7ddce3d81f20ce6d4f8e55d6..b87992927201715cd2c8f7a6ffd94f3e488412b9 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletObject.cpp @@ -46,7 +46,7 @@ namespace SimDynamics CollisionModelPtr colModel = o->getCollisionModel(); if (!colModel) { - VR_WARNING << "Building empty collision shape for object " << o->getName() << endl; + VR_WARNING << "Building empty collision shape for object " << o->getName() << std::endl; collisionShape.reset(new btEmptyShape()); } else @@ -59,7 +59,7 @@ namespace SimDynamics if (primitives.size() > 0) { - //cout << "Object:" << o->getName() << endl; + //cout << "Object:" << o->getName() << std::endl; //o->print(); btCompoundShape* compoundShape = new btCompoundShape(true); @@ -69,7 +69,7 @@ namespace SimDynamics Eigen::Matrix4f localComTransform; localComTransform.setIdentity(); localComTransform.block(0, 3, 3, 1) = -o->getCoMLocal(); - //cout << "localComTransform:\n" << localComTransform << endl; + //cout << "localComTransform:\n" << localComTransform << std::endl; currentTransform = localComTransform; @@ -77,8 +77,8 @@ namespace SimDynamics { currentTransform *= (*it)->transform; //currentTransform = localComTransform * (*it)->transform; - //cout << "primitive: (*it)->transform:\n" << (*it)->transform << endl; - //cout << "primitive: currentTransform:\n" << currentTransform << endl; + //cout << "primitive: (*it)->transform:\n" << (*it)->transform << std::endl; + //cout << "primitive: currentTransform:\n" << currentTransform << std::endl; compoundShape->addChildShape(BulletEngine::getPoseBullet(currentTransform), getShapeFromPrimitive(*it)); } @@ -126,12 +126,12 @@ namespace SimDynamics //type = eKinematic; if (colModel) { - VR_WARNING << "Object:" << o->getName() << ": mass == 0 -> SimulationType must not be eDynamic! Setting mass to 1" << endl; + VR_WARNING << "Object:" << o->getName() << ": mass == 0 -> SimulationType must not be eDynamic! Setting mass to 1" << std::endl; } } #ifdef DEBUG_FIXED_OBJECTS - cout << "TEST" << endl; + std::cout << "TEST" << std::endl; mass = 0; localInertia.setValue(0.0f, 0.0f, 0.0f); #else @@ -166,7 +166,7 @@ namespace SimDynamics rigidBody->setUserPointer((void*)(this)); #if 0 rigidBody->setCollisionFlags(btCollisionObject::CF_STATIC_OBJECT); - cout << "TEST3" << endl; + std::cout << "TEST3" << std::endl; #endif setPoseIntern(o->getGlobalPose()); diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGL/Win32AppMain.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGL/Win32AppMain.cpp index 1626c7dce31377a03f47dd9ba50783df66f59cbe..52fcc55fe9725e1d24dd276f1829060a9a66c35e 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGL/Win32AppMain.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGL/Win32AppMain.cpp @@ -303,7 +303,7 @@ int WINAPI WinMain(HINSTANCE hInstance, HINSTANCE hPrevInstance, gDemoApplication->reshape(sWidth, sHeight); //RedirectIOToConsole(); - //cout << "Test output to cout" << endl; + //cout << "Test output to cout" << std::endl; // program main loop while (!quit) { diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.cpp index 0fd864f9d916ef84ff85948c375bcfe0a725b78b..fdcb9f722c705223ce63aba57857c47135486e99 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletOpenGLViewer.cpp @@ -47,7 +47,7 @@ namespace SimDynamics if (m_dynamicsWorld) { btScalar dt1 = 0.015;//btScalar(ms / 1000000.0f); -// std::cout << "dt1: " << dt1 << " internal: " << (1./140.f) << endl; +// std::cout << "dt1: " << dt1 << " internal: " << (1./140.f) << std::endl; m_dynamicsWorld->stepSimulation(dt1, 100, 1./140.f); //optional but useful: debug drawing diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp index 9d91237304006d0ef87d3e0d6cd6aef01b97f101..aac25403357e76031eeef88b05c8d4af42340d68 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp @@ -53,7 +53,7 @@ namespace SimDynamics if (!hasLink(node)) { - VR_WARNING << "Ignoring FT sensor " << ftSensor->getName() << ". Must be linked to a joint" << endl; + VR_WARNING << "Ignoring FT sensor " << ftSensor->getName() << ". Must be linked to a joint" << std::endl; } else { @@ -113,7 +113,7 @@ namespace SimDynamics } else { - VR_WARNING << "No body between " << parent->getName() << " and " << joint->getName() << ", skipping " << parent->getName() << endl; + VR_WARNING << "No body between " << parent->getName() << " and " << joint->getName() << ", skipping " << parent->getName() << std::endl; } /*else { @@ -187,7 +187,7 @@ namespace SimDynamics if (!rn2) { - VR_ERROR << "Error while processing robot node <" << rn->getName() << ">: Ignored collision model <" << i << "> is not part of robot..." << endl; + VR_ERROR << "Error while processing robot node <" << rn->getName() << ">: Ignored collision model <" << i << "> is not part of robot..." << std::endl; } else { @@ -349,7 +349,7 @@ namespace SimDynamics if (joint->getJointValue() != 0.0f) { - VR_WARNING << joint->getName() << ": joint values != 0 may produce a wrong setup, setting joint value to zero" << endl; + VR_WARNING << joint->getName() << ": joint values != 0 may produce a wrong setup, setting joint value to zero" << std::endl; joint->setJointValue(0); } @@ -423,7 +423,7 @@ namespace SimDynamics } else { - VR_WARNING << "Creating fixed joint between " << bodyA->getName() << " and " << bodyB->getName() << ". This might result in some artefacts (e.g. no strict ridgid connection)" << endl; + VR_WARNING << "Creating fixed joint between " << bodyA->getName() << " and " << bodyB->getName() << ". This might result in some artefacts (e.g. no strict ridgid connection)" << std::endl; // create fixed joint jointbt = createFixedJoint(btBody1, btBody2, anchor_inNode1, anchor_inNode2); } @@ -510,7 +510,7 @@ namespace SimDynamics void BulletRobot::actuateJoints(double dt) { MutexLockPtr lock = getScopedLock(); - //cout << "=== === BulletRobot: actuateJoints() 1 === " << this << endl; + //cout << "=== === BulletRobot: actuateJoints() 1 === " << this << std::endl; auto it = actuationTargets.begin(); @@ -519,7 +519,7 @@ namespace SimDynamics for (; it != actuationTargets.end(); it++) { - //cout << "it:" << it->first << ", name: " << it->first->getName() << endl; + //cout << "it:" << it->first << ", name: " << it->first->getName() << std::endl; VelocityMotorController& controller = actuationControllers[it->first]; if (!it->second.node->isRotationalJoint() && !it->second.node->isTranslationalJoint()) @@ -645,7 +645,7 @@ namespace SimDynamics } /*if (it->second.node->getName() == "ArmL6_Elb2") { - cout << "ELBOW - pos act:" << posActual << ",\t posTarget: " << posTarget << ",\t delta: " << deltaPos << ",\t , vel target:" << velocityTarget << ",\t pid vel:" << targetVelocity << endl; + std::cout << "ELBOW - pos act:" << posActual << ",\t posTarget: " << posTarget << ",\t delta: " << deltaPos << ",\t , vel target:" << velocityTarget << ",\t pid vel:" << targetVelocity << std::endl; }*/ btScalar maxImpulse = bulletMaxMotorImulse; @@ -653,7 +653,7 @@ namespace SimDynamics if (it->second.node->getMaxTorque() > 0) { maxImpulse = it->second.node->getMaxTorque() * btScalar(dt) * BulletObject::ScaleFactor * BulletObject::ScaleFactor * BulletObject::ScaleFactor; - //cout << "node:" << it->second.node->getName() << ", max impulse: " << maxImpulse << ", dt:" << dt << ", maxImp:" << it->second.node->getMaxTorque() << endl; + //cout << "node:" << it->second.node->getName() << ", max impulse: " << maxImpulse << ", dt:" << dt << ", maxImp:" << it->second.node->getMaxTorque() << std::endl; } if (fabs(targetVelocity) > 0.00001) { @@ -675,7 +675,7 @@ namespace SimDynamics } } - //cout << endl; + //cout << std::endl; setPoseNonActuatedRobotNodes(); } @@ -796,7 +796,7 @@ namespace SimDynamics } } - VR_WARNING << "No link with nodes: " << object1->getName() << " and " << object2->getName() << endl; + VR_WARNING << "No link with nodes: " << object1->getName() << " and " << object2->getName() << std::endl; return LinkInfo(); } @@ -845,13 +845,13 @@ namespace SimDynamics if (!robot || !robot->hasRobotNode(nodeName)) { - VR_ERROR << "no node with name " << nodeName << endl; + VR_ERROR << "no node with name " << nodeName << std::endl; return result; } if (!object) { - VR_ERROR << "no object " << endl; + VR_ERROR << "no object " << std::endl; return result; } @@ -859,7 +859,7 @@ namespace SimDynamics if (!bo) { - VR_ERROR << "no bullet object " << endl; + VR_ERROR << "no bullet object " << std::endl; return result; } @@ -882,7 +882,7 @@ namespace SimDynamics if (!drn) { - VR_ERROR << "No dynamics object..." << endl; + VR_ERROR << "No dynamics object..." << std::endl; return result; } } @@ -891,7 +891,7 @@ namespace SimDynamics if (!bo) { - VR_ERROR << "no bullet robot object " << endl; + VR_ERROR << "no bullet robot object " << std::endl; return result; } @@ -941,7 +941,7 @@ namespace SimDynamics links.push_back(*result); - VR_INFO << "Attached object " << object->getName() << " to node " << nodeName << endl; + VR_INFO << "Attached object " << object->getName() << " to node " << nodeName << std::endl; return result; } @@ -951,13 +951,13 @@ namespace SimDynamics if (!robot) { - VR_ERROR << "no robot " << endl; + VR_ERROR << "no robot " << std::endl; return false; } if (!object) { - VR_ERROR << "no object " << endl; + VR_ERROR << "no object " << std::endl; return false; } @@ -965,7 +965,7 @@ namespace SimDynamics if (!bo) { - VR_ERROR << "no bullet object " << endl; + VR_ERROR << "no bullet object " << std::endl; return false; } @@ -974,7 +974,7 @@ namespace SimDynamics if (ls.size() == 0) { - VR_ERROR << "No link with object " << object->getName() << endl; + VR_ERROR << "No link with object " << object->getName() << std::endl; return true; // not a failure, object is not attached } @@ -983,7 +983,7 @@ namespace SimDynamics res = res & removeLink(l); } - VR_INFO << "Detached object " << object->getName() << " from robot " << robot->getName() << endl; + VR_INFO << "Detached object " << object->getName() << " from robot " << robot->getName() << std::endl; return res; } @@ -1011,7 +1011,7 @@ namespace SimDynamics { if (!hasLink(node)) { - VR_ERROR << "No link for node " << node->getName() << endl; + VR_ERROR << "No link for node " << node->getName() << std::endl; return; } @@ -1021,11 +1021,11 @@ namespace SimDynamics { if (node->isTranslationalJoint() && ignoreTranslationalJoints) { - VR_WARNING << "Translational joints ignored. (ignoring node " << node->getName() << ")." << endl; + VR_WARNING << "Translational joints ignored. (ignoring node " << node->getName() << ")." << std::endl; } else { - VR_ERROR << "Only Revolute and translational joints implemented so far (ignoring node " << node->getName() << ")." << endl; + VR_ERROR << "Only Revolute and translational joints implemented so far (ignoring node " << node->getName() << ")." << std::endl; } } } @@ -1037,7 +1037,7 @@ namespace SimDynamics if (!hasLink(node)) { - VR_ERROR << "No link for node " << node->getName() << endl; + VR_ERROR << "No link for node " << node->getName() << std::endl; return; } @@ -1049,7 +1049,7 @@ namespace SimDynamics } else { - VR_ERROR << "Only Revolute and Prismatic joints implemented so far (node: " << node->getName() << ")..." << endl; + VR_ERROR << "Only Revolute and Prismatic joints implemented so far (node: " << node->getName() << ")..." << std::endl; } } @@ -1060,7 +1060,7 @@ namespace SimDynamics if (!hasLink(rn)) { - //VR_ERROR << "No link with node " << rn->getName() << endl; + //VR_ERROR << "No link with node " << rn->getName() << std::endl; return 0.0f; } @@ -1093,7 +1093,7 @@ namespace SimDynamics if (!hasLink(rn)) { - //VR_ERROR << "No link with node " << rn->getName() << endl; + //VR_ERROR << "No link with node " << rn->getName() << std::endl; return 0.0f; } @@ -1124,7 +1124,7 @@ namespace SimDynamics if (!hasLink(rn)) { - //VR_ERROR << "No link with node " << rn->getName() << endl; + //VR_ERROR << "No link with node " << rn->getName() << std::endl; return 0.0f; } @@ -1156,7 +1156,7 @@ namespace SimDynamics } else { - VR_WARNING << "Only translational and rotational joints implemented." << endl; + VR_WARNING << "Only translational and rotational joints implemented." << std::endl; return 0.0; } } @@ -1176,7 +1176,7 @@ namespace SimDynamics if (!hasLink(rn)) { - //VR_ERROR << "No link with node " << rn->getName() << endl; + //VR_ERROR << "No link with node " << rn->getName() << std::endl; return result; } @@ -1189,7 +1189,7 @@ namespace SimDynamics } else { - VR_WARNING << "Only translational and rotational joints implemented." << endl; + VR_WARNING << "Only translational and rotational joints implemented." << std::endl; } return result; @@ -1202,7 +1202,7 @@ namespace SimDynamics if (!hasLink(rn)) { - //VR_ERROR << "No link with node " << rn->getName() << endl; + //VR_ERROR << "No link with node " << rn->getName() << std::endl; return 0.0; } @@ -1219,7 +1219,7 @@ namespace SimDynamics } else { - VR_WARNING << "Only translational and rotational joints implemented." << endl; + VR_WARNING << "Only translational and rotational joints implemented." << std::endl; } return 0.0; } @@ -1233,7 +1233,7 @@ namespace SimDynamics if (!hasLink(rn)) { - //VR_ERROR << "No link with node " << rn->getName() << endl; + //VR_ERROR << "No link with node " << rn->getName() << std::endl; return result; } @@ -1246,7 +1246,7 @@ namespace SimDynamics } else { - VR_WARNING << "Only translational and rotational joints implemented." << endl; + VR_WARNING << "Only translational and rotational joints implemented." << std::endl; } return result; @@ -1259,7 +1259,7 @@ namespace SimDynamics if (!bo) { - VR_ERROR << "Could not cast object..." << endl; + VR_ERROR << "Could not cast object..." << std::endl; return Eigen::Matrix4f::Identity(); } @@ -1299,11 +1299,11 @@ namespace SimDynamics if (boost::math::isnan(vel(0)) || boost::math::isnan(vel(1)) || boost::math::isnan(vel(2))) { - VR_ERROR << "NAN result: getLinearVelocity:" << bo->getName() << ", i:" << i << endl; + VR_ERROR << "NAN result: getLinearVelocity:" << bo->getName() << ", i:" << i << std::endl; node->print(); - VR_ERROR << "BULLETOBJECT com:" << bo->getCom() << endl; - VR_ERROR << "BULLETOBJECT: ang vel:" << bo->getAngularVelocity() << endl; - VR_ERROR << "BULLETOBJECT:" << bo->getRigidBody()->getWorldTransform().getOrigin() << endl; + VR_ERROR << "BULLETOBJECT com:" << bo->getCom() << std::endl; + VR_ERROR << "BULLETOBJECT: ang vel:" << bo->getAngularVelocity() << std::endl; + VR_ERROR << "BULLETOBJECT:" << bo->getRigidBody()->getWorldTransform().getOrigin() << std::endl; } @@ -1314,7 +1314,7 @@ namespace SimDynamics if (fabs(totalMass) < 1e-5) { - VR_ERROR << "Little mass: " << totalMass << ". Could not compute com velocity..." << endl; + VR_ERROR << "Little mass: " << totalMass << ". Could not compute com velocity..." << std::endl; } else { @@ -1448,7 +1448,7 @@ namespace SimDynamics // just a sanity check if (lastSize == notActuatedNodes.size()) { - VR_ERROR << "Internal error?!" << endl; + VR_ERROR << "Internal error?!" << std::endl; return; } else diff --git a/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp b/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp index 6afa751a97e2d7bba80df886e34ed0083449f5cf..b3a2feac621b6d1737542b6600ab1fdd790b27e2 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp @@ -70,7 +70,7 @@ namespace SimDynamics if (std::isnan(_transform.getOrigin().x()) || std::isnan(_transform.getOrigin().y()) || std::isnan(_transform.getOrigin().z())) { - VR_ERROR << "NAN transform!!!" << endl; + VR_ERROR << "NAN transform!!!" << std::endl; } #endif @@ -145,7 +145,7 @@ namespace SimDynamics if (std::isnan(ja)) { - VR_ERROR << "NAN !!!" << endl; + VR_ERROR << "NAN !!!" << std::endl; } #endif @@ -161,14 +161,14 @@ namespace SimDynamics if (rn->getName() == "Shoulder 1 L") { - cout << "Shoulder 1 L:" << ja << ", speed:" << bdr->getJointSpeed(rn) << endl; + std::cout << "Shoulder 1 L:" << ja << ", speed:" << bdr->getJointSpeed(rn) << std::endl; } #endif } /*else { - VR_WARNING << "Could not determine dynamic robot?!" << endl; + VR_WARNING << "Could not determine dynamic robot?!" << std::endl; }*/ } else diff --git a/SimDynamics/DynamicsEngine/DynamicsEngine.cpp b/SimDynamics/DynamicsEngine/DynamicsEngine.cpp index 2e4f97af485dc7553f92bf3e0f610ee048e59b22..a2742e202f2510af6c1079b1b659c379e00c5836 100644 --- a/SimDynamics/DynamicsEngine/DynamicsEngine.cpp +++ b/SimDynamics/DynamicsEngine/DynamicsEngine.cpp @@ -105,7 +105,7 @@ namespace SimDynamics { if (robot->getRobot() == r->getRobot()) { - VR_ERROR << "Only one DynamicsWrapper per robot allowed. Robot " << r->getName() << endl; + VR_ERROR << "Only one DynamicsWrapper per robot allowed. Robot " << r->getName() << std::endl; return false; } } @@ -137,7 +137,7 @@ namespace SimDynamics if (!r) { - VR_ERROR << "No robot with name " << robotName << endl; + VR_ERROR << "No robot with name " << robotName << std::endl; return false; } @@ -167,7 +167,7 @@ namespace SimDynamics if (!r) { - VR_ERROR << "No robot with name " << robotName << endl; + VR_ERROR << "No robot with name " << robotName << std::endl; return false; } diff --git a/SimDynamics/DynamicsEngine/DynamicsObject.cpp b/SimDynamics/DynamicsEngine/DynamicsObject.cpp index 44a1ab3e9f013560a90a1cc96c0aee89089ac38e..c72c8800b4d2d1055036c66d05d75a0a9d4ea24a 100644 --- a/SimDynamics/DynamicsEngine/DynamicsObject.cpp +++ b/SimDynamics/DynamicsEngine/DynamicsObject.cpp @@ -36,7 +36,7 @@ namespace SimDynamics } if (sceneObject->getSimulationType() == VirtualRobot::SceneObject::Physics::eStatic) { - VR_ERROR << "Could not move static object, use kinematic instead, aborting..." << endl; + VR_ERROR << "Could not move static object, use kinematic instead, aborting..." << std::endl; return; } try diff --git a/SimDynamics/DynamicsEngine/DynamicsRobot.cpp b/SimDynamics/DynamicsEngine/DynamicsRobot.cpp index 5d3fd8be637844dc9d28362ec8225e5b7268c17f..079587e5751abadbfa52915846050d6c03e51e48 100644 --- a/SimDynamics/DynamicsEngine/DynamicsRobot.cpp +++ b/SimDynamics/DynamicsEngine/DynamicsRobot.cpp @@ -127,7 +127,7 @@ namespace SimDynamics if (node->getName() == "Elbow R") { - cout << "##### +++++ New Node target:" << node->getName() << ", jointValue:" << jointValue << endl; + std::cout << "##### +++++ New Node target:" << node->getName() << ", jointValue:" << jointValue << std::endl; } #endif diff --git a/SimDynamics/DynamicsEngine/DynamicsUtils.cpp b/SimDynamics/DynamicsEngine/DynamicsUtils.cpp index a46f0c3d2458c1171ece6d2936c8cace2b60155b..55089edcbe3fe9b532c3a5143ac423911de6736e 100644 --- a/SimDynamics/DynamicsEngine/DynamicsUtils.cpp +++ b/SimDynamics/DynamicsEngine/DynamicsUtils.cpp @@ -149,7 +149,7 @@ namespace SimDynamics void VelocityMotorController::setCurrentVelocity(double vel) { -// std::cout << "Velocity of " << name << " is now " << vel << endl; +// std::cout << "Velocity of " << name << " is now " << vel << std::endl; velocity = vel; } diff --git a/SimDynamics/DynamicsWorld.cpp b/SimDynamics/DynamicsWorld.cpp index 1f9ae255a7f862fe362d8d84bd81f00a8136ec53..6dcccfff488d1bd803496f0e2b376a6d7680e6ca 100644 --- a/SimDynamics/DynamicsWorld.cpp +++ b/SimDynamics/DynamicsWorld.cpp @@ -57,7 +57,7 @@ namespace SimDynamics } else { - VR_WARNING << "Dynamics world is already initialized..." << endl; + VR_WARNING << "Dynamics world is already initialized..." << std::endl; } } diff --git a/SimDynamics/examples/BulletDebugViewer/BulletDebugViewerGlut.cpp b/SimDynamics/examples/BulletDebugViewer/BulletDebugViewerGlut.cpp index 0103999771e8fde0557a98dc29869706bbb245e6..614cfb751e7b7749d6a6e893dc53e2c67007b17a 100644 --- a/SimDynamics/examples/BulletDebugViewer/BulletDebugViewerGlut.cpp +++ b/SimDynamics/examples/BulletDebugViewer/BulletDebugViewerGlut.cpp @@ -130,7 +130,7 @@ int main(int argc, char* argv[]) VirtualRobot::RuntimeEnvironment::processCommandLine(argc, argv); VirtualRobot::RuntimeEnvironment::print(); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; //std::string robFile("robots/examples/SimpleRobot/Joint5.xml"); @@ -150,7 +150,7 @@ int main(int argc, char* argv[]) } } - cout << "Using robot at " << robFile << endl; + std::cout << "Using robot at " << robFile << std::endl; @@ -209,7 +209,7 @@ int main(int argc, char* argv[]) //viewer.enableContraintsDebugDrawing(); #if 0 - cout << "TEST7" << endl; + std::cout << "TEST7" << std::endl; ObstaclePtr o = Obstacle::createBox(10, 10, 1500); DynamicsObjectPtr do1 = DynamicsWorld::GetWorld()->CreateDynamicsObject(o, DynamicsObject::eStatic); ObstaclePtr o2 = Obstacle::createBox(10, 10, 1000); @@ -229,11 +229,11 @@ int main(int argc, char* argv[]) e->disableCollision(do2.get(),dos[i].get()); if (e->checkCollisionEnabled(do1.get(),dos[i].get())) { - cout << "OOPS" << endl; + std::cout << "OOPS" << std::endl; } if (e->checkCollisionEnabled(do2.get(),dos[i].get())) { - cout << "OOPS" << endl; + std::cout << "OOPS" << std::endl; } }*/ e->addObject(do1); diff --git a/SimDynamics/examples/SimDynamicsViewer/SimDynamicsViewer.cpp b/SimDynamics/examples/SimDynamicsViewer/SimDynamicsViewer.cpp index 1f63433875cbccd4e4beaefe23b1db3ff3becc95..52bc72fad72ee5565cb8e03b00ad90277aa50de6 100644 --- a/SimDynamics/examples/SimDynamicsViewer/SimDynamicsViewer.cpp +++ b/SimDynamics/examples/SimDynamicsViewer/SimDynamicsViewer.cpp @@ -33,7 +33,7 @@ int main(int argc, char* argv[]) VirtualRobot::RuntimeEnvironment::processCommandLine(argc, argv); VirtualRobot::RuntimeEnvironment::print(); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; // --robot "robots/iCub/iCub.xml" //std::string filename("robots/iCub/iCub.xml"); std::string filename("robots/ArmarIII/ArmarIII.xml"); @@ -51,7 +51,7 @@ int main(int argc, char* argv[]) } } - cout << "Using robot at " << filename << endl; + std::cout << "Using robot at " << filename << std::endl; SimDynamicsWindow rw(filename); diff --git a/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp b/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp index 661cc3a839b14451842da54ac3331b6d03ee06f0..788f59343afd2fb9bc9031921fa124e6e02ab8db 100644 --- a/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp +++ b/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp @@ -31,7 +31,7 @@ using namespace SimDynamics; SimDynamicsWindow::SimDynamicsWindow(std::string& sRobotFilename) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; //this->setCaption(QString("ShowRobot - KIT - Humanoids Group")); //resize(1100, 768); @@ -312,7 +312,7 @@ void SimDynamicsWindow::updateJoints() { if (!robot) { - cout << " ERROR while creating list of nodes" << endl; + std::cout << " ERROR while creating list of nodes" << std::endl; return; } @@ -342,7 +342,7 @@ void SimDynamicsWindow::updateJoints() bool SimDynamicsWindow::loadRobot(std::string robotFilename) { - cout << "Loading Robot from " << robotFilename << endl; + std::cout << "Loading Robot from " << robotFilename << std::endl; try { @@ -350,14 +350,14 @@ bool SimDynamicsWindow::loadRobot(std::string robotFilename) } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return false; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return false; } @@ -379,8 +379,8 @@ bool SimDynamicsWindow::loadRobot(std::string robotFilename) } catch (VirtualRobotException& e) { - cout << " ERROR while building dynamic robot" << endl; - cout << e.what(); + std::cout << " ERROR while building dynamic robot" << std::endl; + std::cout << e.what(); return false; } @@ -454,10 +454,10 @@ void SimDynamicsWindow::updateJointInfo() if (bulletRN) { - // cout << "FORCE: " << bulletRN->getRigidBody()->getTotalForce()[0] << ", " << bulletRN->getRigidBody()->getTotalForce()[1] << ", " << bulletRN->getRigidBody()->getTotalForce()[2] << endl; - // cout << "TORQUE: " << bulletRN->getRigidBody()->getTotalTorque()[0] << ", " << bulletRN->getRigidBody()->getTotalTorque()[1] << ", " << bulletRN->getRigidBody()->getTotalTorque()[2] << endl; - // cout << "getLinearVelocity: " << bulletRN->getRigidBody()->getLinearVelocity()[0] << ", " << bulletRN->getRigidBody()->getLinearVelocity()[1] << ", " << bulletRN->getRigidBody()->getLinearVelocity()[2] << endl; - // cout << "getAngularVelocity: " << bulletRN->getRigidBody()->getAngularVelocity()[0] << ", " << bulletRN->getRigidBody()->getAngularVelocity()[1] << ", " << bulletRN->getRigidBody()->getAngularVelocity()[2] << endl; + // std::cout << "FORCE: " << bulletRN->getRigidBody()->getTotalForce()[0] << ", " << bulletRN->getRigidBody()->getTotalForce()[1] << ", " << bulletRN->getRigidBody()->getTotalForce()[2] << std::endl; + // std::cout << "TORQUE: " << bulletRN->getRigidBody()->getTotalTorque()[0] << ", " << bulletRN->getRigidBody()->getTotalTorque()[1] << ", " << bulletRN->getRigidBody()->getTotalTorque()[2] << std::endl; + // std::cout << "getLinearVelocity: " << bulletRN->getRigidBody()->getLinearVelocity()[0] << ", " << bulletRN->getRigidBody()->getLinearVelocity()[1] << ", " << bulletRN->getRigidBody()->getLinearVelocity()[2] << std::endl; + // std::cout << "getAngularVelocity: " << bulletRN->getRigidBody()->getAngularVelocity()[0] << ", " << bulletRN->getRigidBody()->getAngularVelocity()[1] << ", " << bulletRN->getRigidBody()->getAngularVelocity()[2] << std::endl; } @@ -496,9 +496,9 @@ void SimDynamicsWindow::updateJointInfo() UI.label_ForceTorqueB->setText(QString::fromStdString(streamFTB.str())); - // cout << "ForceTorqueA:" << endl; + // std::cout << "ForceTorqueA:" << std::endl; // MathTools::print(ftA); - // cout << "ForceTorqueB:" << endl; + // std::cout << "ForceTorqueB:" << std::endl; // MathTools::print(ftB); forceSep->removeAllChildren(); @@ -515,10 +515,10 @@ void SimDynamicsWindow::updateJointInfo() SoSeparator* arrowForceA = CoinVisualizationFactory::CreateArrow(n, l, w, VisualizationFactory::Color::Red()); /* - cout << "FORCE_A: " << linkInfo.dynNode1->getRigidBody()->getTotalForce()[0] << "," << linkInfo.dynNode1->getRigidBody()->getTotalForce()[1] << "," << linkInfo.dynNode1->getRigidBody()->getTotalForce()[2] << endl; - cout << "TORQUEA: " << linkInfo.dynNode1->getRigidBody()->getTotalTorque()[0] << "," << linkInfo.dynNode1->getRigidBody()->getTotalTorque()[1] << "," << linkInfo.dynNode1->getRigidBody()->getTotalTorque()[2] << endl; - cout << "FORCE_B: " << linkInfo.dynNode2->getRigidBody()->getTotalForce()[0] << "," << linkInfo.dynNode2->getRigidBody()->getTotalForce()[1] << "," << linkInfo.dynNode2->getRigidBody()->getTotalForce()[2] << endl; - cout << "TORQUEB: " << linkInfo.dynNode2->getRigidBody()->getTotalTorque()[0] << "," << linkInfo.dynNode2->getRigidBody()->getTotalTorque()[1] << "," << linkInfo.dynNode2->getRigidBody()->getTotalTorque()[2] << endl; + std::cout << "FORCE_A: " << linkInfo.dynNode1->getRigidBody()->getTotalForce()[0] << "," << linkInfo.dynNode1->getRigidBody()->getTotalForce()[1] << "," << linkInfo.dynNode1->getRigidBody()->getTotalForce()[2] << std::endl; + std::cout << "TORQUEA: " << linkInfo.dynNode1->getRigidBody()->getTotalTorque()[0] << "," << linkInfo.dynNode1->getRigidBody()->getTotalTorque()[1] << "," << linkInfo.dynNode1->getRigidBody()->getTotalTorque()[2] << std::endl; + std::cout << "FORCE_B: " << linkInfo.dynNode2->getRigidBody()->getTotalForce()[0] << "," << linkInfo.dynNode2->getRigidBody()->getTotalForce()[1] << "," << linkInfo.dynNode2->getRigidBody()->getTotalForce()[2] << std::endl; + std::cout << "TORQUEB: " << linkInfo.dynNode2->getRigidBody()->getTotalTorque()[0] << "," << linkInfo.dynNode2->getRigidBody()->getTotalTorque()[1] << "," << linkInfo.dynNode2->getRigidBody()->getTotalTorque()[2] << std::endl; */ // show as nodeA local coords system @@ -545,7 +545,7 @@ void SimDynamicsWindow::updateJointInfo() //Eigen::Vector3f TBGlobal = ftB.tail(3) ; Eigen::VectorXf torqueJointGlobal = bulletRobot->getJointForceTorqueGlobal(linkInfo);//= TBGlobal - (comBGlobal-jointGlobal).cross(FBGlobal) * 0.001; - // cout << "torqueJointGlobal: " << torqueJointGlobal << endl; + // std::cout << "torqueJointGlobal: " << torqueJointGlobal << std::endl; std::stringstream streamFTJoint; streamFTJoint.precision(1); streamFTJoint << "ForceTorqueJoint: " << std::fixed; @@ -589,10 +589,10 @@ void SimDynamicsWindow::updateJointInfo() else { btJointFeedback* feedback = linkInfo.joint->getJointFeedback(); - cout << "feedback->m_appliedForceBodyA: " << feedback->m_appliedForceBodyA[0] << "," << feedback->m_appliedForceBodyA[1] << "," << feedback->m_appliedForceBodyA[2] << endl; - cout << "feedback->m_appliedForceBodyB: " << feedback->m_appliedForceBodyB[0] << "," << feedback->m_appliedForceBodyB[1] << "," << feedback->m_appliedForceBodyB[2] << endl; - cout << "feedback->m_appliedTorqueBodyA: " << feedback->m_appliedTorqueBodyA[0] << "," << feedback->m_appliedTorqueBodyA[1] << "," << feedback->m_appliedTorqueBodyA[2] << endl; - cout << "feedback->m_appliedTorqueBodyB: " << feedback->m_appliedTorqueBodyB[0] << "," << feedback->m_appliedTorqueBodyB[1] << "," << feedback->m_appliedTorqueBodyB[2] << endl; + std::cout << "feedback->m_appliedForceBodyA: " << feedback->m_appliedForceBodyA[0] << "," << feedback->m_appliedForceBodyA[1] << "," << feedback->m_appliedForceBodyA[2] << std::endl; + std::cout << "feedback->m_appliedForceBodyB: " << feedback->m_appliedForceBodyB[0] << "," << feedback->m_appliedForceBodyB[1] << "," << feedback->m_appliedForceBodyB[2] << std::endl; + std::cout << "feedback->m_appliedTorqueBodyA: " << feedback->m_appliedTorqueBodyA[0] << "," << feedback->m_appliedTorqueBodyA[1] << "," << feedback->m_appliedTorqueBodyA[2] << std::endl; + std::cout << "feedback->m_appliedTorqueBodyB: " << feedback->m_appliedTorqueBodyB[0] << "," << feedback->m_appliedTorqueBodyB[1] << "," << feedback->m_appliedTorqueBodyB[2] << std::endl; } */ @@ -740,7 +740,7 @@ void SimDynamicsWindow::updateJointInfo() // print some joint info if (viewer->engineRunning()) { - cout << info << endl; + std::cout << info << std::endl; } #endif @@ -834,7 +834,7 @@ void SimDynamicsWindow::updateContactVisu() for (auto & i : c) { - cout << "Contact: " << i.objectAName << " + " << i.objectBName << endl; + std::cout << "Contact: " << i.objectAName << " + " << i.objectBName << std::endl; SoSeparator* normal = new SoSeparator; SoMatrixTransform* m = new SoMatrixTransform; SbMatrix ma; @@ -996,7 +996,7 @@ void SimDynamicsWindow::addObject() if (counter > 100) { - cout << "Error, could not find valid pose" << endl; + std::cout << "Error, could not find valid pose" << std::endl; return; } } diff --git a/VirtualRobot/CollisionDetection/CDManager.cpp b/VirtualRobot/CollisionDetection/CDManager.cpp index ac3d4cd0f5621f6d5cea059ab5440947abb80f43..52b0ab53d40b3ab2f0599e94850db15d2b5af4b9 100644 --- a/VirtualRobot/CollisionDetection/CDManager.cpp +++ b/VirtualRobot/CollisionDetection/CDManager.cpp @@ -34,7 +34,7 @@ namespace VirtualRobot { if (m->getCollisionChecker() != colChecker) { - VR_WARNING << "CollisionModel of SceneObjectSet '" << m->getName() << "' is linked to a different instance of collision checker than this CollisionManager..." << endl; + VR_WARNING << "CollisionModel of SceneObjectSet '" << m->getName() << "' is linked to a different instance of collision checker than this CollisionManager..." << std::endl; } auto tmpColModels = colModels; // colModels is changed in the next loop, so we need a copy for (const auto& colModel : tmpColModels) @@ -81,7 +81,7 @@ namespace VirtualRobot { if (!m || !colChecker) { - VR_WARNING << " NULL data..." << endl; + VR_WARNING << " NULL data..." << std::endl; return false; } @@ -109,7 +109,7 @@ namespace VirtualRobot if (!m || !colChecker) { - VR_WARNING << " NULL data..." << endl; + VR_WARNING << " NULL data..." << std::endl; return 0.0f; } diff --git a/VirtualRobot/CollisionDetection/CollisionChecker.cpp b/VirtualRobot/CollisionDetection/CollisionChecker.cpp index 6c6f72222095bee1bafb51ce7f939d9c46a41cee..30806780a234245b1acf33ec05cb6cec29445c89 100644 --- a/VirtualRobot/CollisionDetection/CollisionChecker.cpp +++ b/VirtualRobot/CollisionDetection/CollisionChecker.cpp @@ -251,7 +251,7 @@ namespace VirtualRobot if (colModels.size() == 0) { - VR_WARNING << "no internal data..." << endl; + VR_WARNING << "no internal data..." << std::endl; return -1.0f; } @@ -308,7 +308,7 @@ namespace VirtualRobot if (model1.size() == 0) { - VR_WARNING << "no internal data..." << endl; + VR_WARNING << "no internal data..." << std::endl; return false; } @@ -339,12 +339,12 @@ namespace VirtualRobot if (vColModels1.size() == 0) { - VR_WARNING << "no internal data for " << model1->getName() << endl; + VR_WARNING << "no internal data for " << model1->getName() << std::endl; return false; } if ( vColModels2.size() == 0) { - VR_WARNING << "no internal data for " << model2->getName() << endl; + VR_WARNING << "no internal data for " << model2->getName() << std::endl; return false; } @@ -414,7 +414,7 @@ namespace VirtualRobot if (vColModels.size() == 0) { - VR_WARNING << "no internal data..." << endl; + VR_WARNING << "no internal data..." << std::endl; return false; } @@ -480,7 +480,7 @@ namespace VirtualRobot if (vColModels1.size() == 0) { - VR_WARNING << "no internal data for " << modelSet->getName() << endl; + VR_WARNING << "no internal data for " << modelSet->getName() << std::endl; return false; } @@ -516,12 +516,12 @@ namespace VirtualRobot } if (model1->getCollisionChecker() != model2->getCollisionChecker() || model1->getCollisionChecker()!=shared_from_this()) { - VR_WARNING << "Could not go on, collision models are linked to different Collision Checker instances." << endl; + VR_WARNING << "Could not go on, collision models are linked to different Collision Checker instances." << std::endl; return false; } if (!isInitialized()) { - VR_WARNING << "not initialized." << endl; + VR_WARNING << "not initialized." << std::endl; return false; } return collisionCheckerImplementation->getAllCollisonTriangles(model1,model2,storePairs); diff --git a/VirtualRobot/CollisionDetection/CollisionModel.cpp b/VirtualRobot/CollisionDetection/CollisionModel.cpp index 6a1f1f3d1b56fecb1c2c963688f8bef566b06777..ea3c2b4b84bd4ed3bd1300ab5d087a66b0936cbb 100644 --- a/VirtualRobot/CollisionDetection/CollisionModel.cpp +++ b/VirtualRobot/CollisionDetection/CollisionModel.cpp @@ -32,7 +32,7 @@ namespace VirtualRobot if (!this->colChecker) { - VR_WARNING << "no col checker..." << endl; + VR_WARNING << "no col checker..." << std::endl; } updateVisualization = true; @@ -64,13 +64,13 @@ namespace VirtualRobot if (!this->colChecker) { - VR_WARNING << "no col checker..." << endl; + VR_WARNING << "no col checker..." << std::endl; } updateVisualization = true; if (!collisionModel) { - VR_WARNING << "internal collision model is NULL for " << name << endl; + VR_WARNING << "internal collision model is NULL for " << name << std::endl; } collisionModelImplementation = std::dynamic_pointer_cast<InternalCollisionModel>(collisionModel->clone(false)); VR_ASSERT(collisionModelImplementation->getPQPModel()); diff --git a/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.cpp b/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.cpp index 21be24ca0f37d732cf5ab529620ce7810477b72e..434e7910a6a8ffb46f6906366b583edce65b0cdf 100644 --- a/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.cpp +++ b/VirtualRobot/CollisionDetection/PQP/CollisionCheckerPQP.cpp @@ -494,18 +494,18 @@ namespace VirtualRobot #if 0 if (flag_collision) { - cout << "ccd result: fResDist:" << fResDist << endl; - cout << "ccd result: numCA:" << numCA << endl; - cout << "ccd result: time_of_contact:" << time_of_contact << endl; - cout << "ccd result: flag_collision:" << flag_collision << endl; - cout << "ccd result: number_of_iteration:" << number_of_iteration << endl; - cout << "ccd result: trans0:" << trans0.Translation().X() << "," << trans0.Translation().Y() << "," << trans0.Translation().Z() << endl; - cout << "ccd result: trans1:" << trans1.Translation().X() << "," << trans1.Translation().Y() << "," << trans1.Translation().Z() << endl; - cout << "ccd result: ccdResult:" << ccdResult << endl; + std::cout << "ccd result: fResDist:" << fResDist << std::endl; + std::cout << "ccd result: numCA:" << numCA << std::endl; + std::cout << "ccd result: time_of_contact:" << time_of_contact << std::endl; + std::cout << "ccd result: flag_collision:" << flag_collision << std::endl; + std::cout << "ccd result: number_of_iteration:" << number_of_iteration << std::endl; + std::cout << "ccd result: trans0:" << trans0.Translation().X() << "," << trans0.Translation().Y() << "," << trans0.Translation().Z() << std::endl; + std::cout << "ccd result: trans1:" << trans1.Translation().X() << "," << trans1.Translation().Y() << "," << trans1.Translation().Z() << std::endl; + std::cout << "ccd result: ccdResult:" << ccdResult << std::endl; } else { - cout << "."; + std::cout << "."; } #endif fStoreTOC = (float)time_of_contact; diff --git a/VirtualRobot/Compression/CompressionBZip2.cpp b/VirtualRobot/Compression/CompressionBZip2.cpp index 59bf64a16bd39ac485aebf24c6bc1aa7e5f37f9b..99605ba8835e7b2f019ff1a4a9dd1165d843141e 100644 --- a/VirtualRobot/Compression/CompressionBZip2.cpp +++ b/VirtualRobot/Compression/CompressionBZip2.cpp @@ -408,7 +408,7 @@ namespace VirtualRobot if (currentError < 0) //== BZ_IO_ERROR) { { - VR_ERROR << "Could not close file?!" << endl; + VR_ERROR << "Could not close file?!" << std::endl; return false; } } @@ -4986,7 +4986,7 @@ preswitch: std::streamoff o(-(int)(bzf->strm.avail_in)); /*if (p>o) { - cout << "Error, expecting position in stream > p?!" << endl; + std::cout << "Error, expecting position in stream > p?!" << std::endl; BZ_SETERR(BZ_SEQUENCE_ERROR); return; }*/ bzf->strm.avail_in = 0; @@ -4996,7 +4996,7 @@ preswitch: } else { - cout << "internal error, expecting handleIn..." << endl; + std::cout << "internal error, expecting handleIn..." << std::endl; BZ_SETERR(BZ_SEQUENCE_ERROR); return; } @@ -5840,7 +5840,7 @@ return_notr: if (mode != eCompress) { - VR_ERROR << "Not in compression mode?!" << endl; + VR_ERROR << "Not in compression mode?!" << std::endl; return false; } @@ -5853,7 +5853,7 @@ return_notr: if (currentError < 0) //== BZ_IO_ERROR) { { - VR_ERROR << "Could not compress data..." << endl; + VR_ERROR << "Could not compress data..." << std::endl; close(); return false; } @@ -5884,7 +5884,7 @@ return_notr: if (mode != eUncompress) { - VR_ERROR << "Not in uncompression mode?!" << endl; + VR_ERROR << "Not in uncompression mode?!" << std::endl; return false; } @@ -5897,7 +5897,7 @@ return_notr: if (currentError < 0) //== BZ_IO_ERROR) { { - VR_ERROR << "Could not uncompress data..." << endl; + VR_ERROR << "Could not uncompress data..." << std::endl; close(); return false; } diff --git a/VirtualRobot/Dynamics/Dynamics.cpp b/VirtualRobot/Dynamics/Dynamics.cpp index 476d33d74d3e8ef904459bfbb235fed64cdd37d3..56563893d8a009fe99d5546c7ac007f79feab67e 100644 --- a/VirtualRobot/Dynamics/Dynamics.cpp +++ b/VirtualRobot/Dynamics/Dynamics.cpp @@ -38,7 +38,7 @@ namespace VirtualRobot { THROW_VR_EXCEPTION("RobotNodeSetPtr for the joints is zero pointer"); } - VERBOSE_OUT << "joint values:\n" << rns->getJointValuesEigen() << endl; + VERBOSE_OUT << "joint values:\n" << rns->getJointValuesEigen() << std::endl; gravity = RigidBodyDynamics::Math::Vector3d(0, 0, -9.81); model = std::shared_ptr<RigidBodyDynamics::Model>(new RigidBodyDynamics::Model()); @@ -132,14 +132,14 @@ namespace VirtualRobot void Dynamics::print() { std::string result = RigidBodyDynamics::Utils::GetModelHierarchy(*model.get()); - cout << "RBDL hierarchy of RNS:" << rns->getName() << endl; - cout << result; + std::cout << "RBDL hierarchy of RNS:" << rns->getName() << std::endl; + std::cout << result; result = RigidBodyDynamics::Utils::GetNamedBodyOriginsOverview(*model.get()); - cout << "RBDL origins of RNS:" << rns->getName() << endl; - cout << result; + std::cout << "RBDL origins of RNS:" << rns->getName() << std::endl; + std::cout << result; result = RigidBodyDynamics::Utils::GetModelDOFOverview(*model.get()); - cout << "RBDL DoF of RNS:" << rns->getName() << endl; - cout << result; + std::cout << "RBDL DoF of RNS:" << rns->getName() << std::endl; + std::cout << result; } std::tuple<Eigen::Matrix3d, Eigen::Vector3d, double> Dynamics::computeCombinedPhysics(const std::set<RobotNodePtr>& nodes, @@ -299,7 +299,7 @@ namespace VirtualRobot if (Dynamics::rns->hasRobotNode(node) && (node->isRotationalJoint() || node->isTranslationalJoint())) { - VR_ERROR << "Skipping joint " << node->getName() << ": multiple joints in row without masses inbetween..." << endl; + VR_ERROR << "Skipping joint " << node->getName() << ": multiple joints in row without masses inbetween..." << std::endl; } } @@ -327,7 +327,7 @@ namespace VirtualRobot RigidBodyDynamics::Math::Matrix3d spatial_rotation = accumulatedTransformPreJoint.block(0, 0, 3, 3).cast<double>(); RigidBodyDynamics::Math::Vector3d spatial_translation = accumulatedTransformPreJoint.col(3).head(3).cast<double>() / 1000.0; RigidBodyDynamics::Math::SpatialTransform spatial_transform = RigidBodyDynamics::Math::SpatialTransform(spatial_rotation, spatial_translation); - VERBOSE_OUT << "****** spatial_translation: " << spatial_translation.transpose() << endl; + VERBOSE_OUT << "****** spatial_translation: " << spatial_translation.transpose() << std::endl; // joint RigidBodyDynamics::Joint joint = RigidBodyDynamics::Joint(RigidBodyDynamics::JointTypeFixed); @@ -341,7 +341,7 @@ namespace VirtualRobot joint = RigidBodyDynamics::Joint(joint_type, joint_axis); - VR_INFO << "Adding Rotational RigidBodyDynamics::Joint" << endl; + VR_INFO << "Adding Rotational RigidBodyDynamics::Joint" << std::endl; } else if (jointNode && jointNode->isTranslationalJoint()) { @@ -351,7 +351,7 @@ namespace VirtualRobot joint = RigidBodyDynamics::Joint(joint_type, joint_axis); - VR_INFO << "Adding Translational RigidBodyDynamics::Joint" << endl; + VR_INFO << "Adding Translational RigidBodyDynamics::Joint" << std::endl; } std::string nodeName; @@ -368,25 +368,25 @@ namespace VirtualRobot nodeID = model->AddBody(parentID, spatial_transform, joint, body, nodeName); this->identifierMap[nodeName] = nodeID; - VERBOSE_OUT << "New body:" << node->getName() << ", " << nodeID << " :" << endl; // Debugging Info - VERBOSE_OUT << "** SPATIAL TRAFO: " << endl << spatial_transform.toMatrix() << endl; - VERBOSE_OUT << "** MASS: " << body.mMass << endl; - VERBOSE_OUT << "** COM: " << body.mCenterOfMass.transpose() << endl; - VERBOSE_OUT << "** INERTIA: " << endl << body.mInertia << endl; - VERBOSE_OUT << "** mIsVirtual: " << body.mIsVirtual << endl; + VERBOSE_OUT << "New body:" << node->getName() << ", " << nodeID << " :" << std::endl; // Debugging Info + VERBOSE_OUT << "** SPATIAL TRAFO: " << endl << spatial_transform.toMatrix() << std::endl; + VERBOSE_OUT << "** MASS: " << body.mMass << std::endl; + VERBOSE_OUT << "** COM: " << body.mCenterOfMass.transpose() << std::endl; + VERBOSE_OUT << "** INERTIA: " << endl << body.mInertia << std::endl; + VERBOSE_OUT << "** mIsVirtual: " << body.mIsVirtual << std::endl; if (jointNode) { - VERBOSE_OUT << "** RigidBodyDynamics::Joint: " << jointNode->getName() << endl; + VERBOSE_OUT << "** RigidBodyDynamics::Joint: " << jointNode->getName() << std::endl; } else { - VERBOSE_OUT << "** RigidBodyDynamics::Joint: none" << endl; + VERBOSE_OUT << "** RigidBodyDynamics::Joint: none" << std::endl; } if (joint.mJointAxes) { - VERBOSE_OUT << "** JOINT AXES " << endl << *(joint.mJointAxes) << endl; + VERBOSE_OUT << "** JOINT AXES " << endl << *(joint.mJointAxes) << std::endl; } // reset pre and post trafos and jointNode @@ -415,7 +415,7 @@ namespace VirtualRobot toRBDLRecursive(model, childRobotNode, accumulatedTransformPreJoint, accumulatedTransformPostJoint, jointNode, nodeID); //} else //{ - // VR_INFO << "skipping RN " << childRobotNode->getName() << " since it is not part of RNS" << endl; + // VR_INFO << "skipping RN " << childRobotNode->getName() << " since it is not part of RNS" << std::endl; //} } } @@ -426,7 +426,7 @@ namespace VirtualRobot void Dynamics::toRBDL(std::shared_ptr<RigidBodyDynamics::Model> model, RobotNodePtr node, RobotNodeSetPtr nodeSet, RobotNodePtr parentNode, int parentID) { - VERBOSE_OUT << "#######ADDING NODE " << node->getName() << endl; + VERBOSE_OUT << "#######ADDING NODE " << node->getName() << std::endl; RobotNodePtr physicsFromChild; int nodeID = parentID; // need to define body, joint and spatial transform @@ -434,7 +434,7 @@ namespace VirtualRobot auto relevantChildNodes = getChildrenWithMass(node, nodeSet); for (auto node : relevantChildNodes) { - VERBOSE_OUT << "Additional child: " << node->getName() << " - " << node->getMass() << " kg" << endl; + VERBOSE_OUT << "Additional child: " << node->getName() << " - " << node->getMass() << " kg" << std::endl; } auto combinedBody = computeCombinedBody(relevantChildNodes, node); @@ -457,7 +457,7 @@ namespace VirtualRobot RigidBodyDynamics::Math::Matrix3d spatial_rotation = trafo.block(0, 0, 3, 3); RigidBodyDynamics::Math::Vector3d spatial_translation = trafo.col(3).head(3) / 1000; - VERBOSE_OUT << "****** spatial_translation: " << spatial_translation.transpose() << endl; + VERBOSE_OUT << "****** spatial_translation: " << spatial_translation.transpose() << std::endl; RigidBodyDynamics::Math::SpatialTransform spatial_transform = RigidBodyDynamics::Math::SpatialTransform(spatial_rotation.transpose(), spatial_translation); @@ -472,7 +472,7 @@ namespace VirtualRobot joint = RigidBodyDynamics::Joint(joint_type, joint_axis); - VERBOSE_OUT << "Rotational RigidBodyDynamics::Joint added:" << endl; + VERBOSE_OUT << "Rotational RigidBodyDynamics::Joint added:" << std::endl; } else if (node->isTranslationalJoint()) { @@ -482,7 +482,7 @@ namespace VirtualRobot joint = RigidBodyDynamics::Joint(joint_type, joint_axis); - VERBOSE_OUT << "translational RigidBodyDynamics::Joint added" << endl; + VERBOSE_OUT << "translational RigidBodyDynamics::Joint added" << std::endl; } if (joint.mJointType != RigidBodyDynamics::JointTypeFixed) @@ -491,12 +491,12 @@ namespace VirtualRobot this->identifierMap[node->getName()] = nodeID; Eigen::VectorXd QDDot = Eigen::VectorXd::Zero(identifierMap.size()); - VERBOSE_OUT << "New body:" << node->getName() << ", " << nodeID << " :" << endl; // Debugging Info - VERBOSE_OUT << "** SPATIAL TRAFO: " << endl << spatial_transform.r << endl << spatial_transform.E << endl; - VERBOSE_OUT << "** MASS: " << body.mMass << endl; - VERBOSE_OUT << "** COM: " << body.mCenterOfMass.transpose() << endl; - VERBOSE_OUT << "** INERTIA: " << endl << body.mInertia << endl; - VERBOSE_OUT << "** mIsVirtual: " << body.mIsVirtual << endl; + VERBOSE_OUT << "New body:" << node->getName() << ", " << nodeID << " :" << std::endl; // Debugging Info + VERBOSE_OUT << "** SPATIAL TRAFO: " << endl << spatial_transform.r << endl << spatial_transform.E << std::endl; + VERBOSE_OUT << "** MASS: " << body.mMass << std::endl; + VERBOSE_OUT << "** COM: " << body.mCenterOfMass.transpose() << std::endl; + VERBOSE_OUT << "** INERTIA: " << endl << body.mInertia << std::endl; + VERBOSE_OUT << "** mIsVirtual: " << body.mIsVirtual << std::endl; Eigen::Vector3d bodyPosition = RigidBodyDynamics::CalcBodyToBaseCoordinates(*model, Eigen::VectorXd::Zero(identifierMap.size()), nodeID, Eigen::Vector3d::Zero(), true); Eigen::Vector3f positionInVirtualRobot = node->getGlobalPosition();//rns->getKinematicRoot()->transformTo(node, zeroVec); auto diff = (positionInVirtualRobot - bodyPosition.cast<float>() * 1000).norm(); @@ -505,11 +505,11 @@ namespace VirtualRobot VR_ERROR << "forward kinematics between virtual robot and rbdl differ: " << diff << " mm"; throw VirtualRobotException("forward kinematics between virtual robot and rbdl differ!"); } - // VERBOSE_OUT << "** position:\n" << bodyPosition << "\nposition in virtual robot:\n" << positionInVirtualRobot << endl << endl; + // VERBOSE_OUT << "** position:\n" << bodyPosition << "\nposition in virtual robot:\n" << positionInVirtualRobot << endl << std::endl; if (joint.mJointAxes) { - VERBOSE_OUT << "** JOINT AXES " << endl << *(joint.mJointAxes) << endl; + VERBOSE_OUT << "** JOINT AXES " << endl << *(joint.mJointAxes) << std::endl; } } diff --git a/VirtualRobot/EndEffector/EndEffector.cpp b/VirtualRobot/EndEffector/EndEffector.cpp index 401bd69aad155813e770682344b314d2a4a77483..6e8a30b7b3189258b3d33f16ec4ec85fd1d7f140 100644 --- a/VirtualRobot/EndEffector/EndEffector.cpp +++ b/VirtualRobot/EndEffector/EndEffector.cpp @@ -313,35 +313,35 @@ namespace VirtualRobot void EndEffector::print() { - cout << " **** EndEffector ****" << endl; + std::cout << " **** EndEffector ****" << std::endl; - cout << " * Name: " << name << endl; - cout << " * Base Node: "; + std::cout << " * Name: " << name << std::endl; + std::cout << " * Base Node: "; if (baseNode) { - cout << baseNode->getName() << endl; + std::cout << baseNode->getName() << std::endl; } else { - cout << "<not set>" << endl; + std::cout << "<not set>" << std::endl; } - cout << " * Static RobotNodes:" << endl; + std::cout << " * Static RobotNodes:" << std::endl; for (auto& i : statics) { - cout << " ** " << i->getName() << endl; + std::cout << " ** " << i->getName() << std::endl; } - cout << " * Actors:" << endl; + std::cout << " * Actors:" << std::endl; for (auto& actor : actors) { actor->print(); } - cout << endl; + std::cout << std::endl; } VirtualRobot::RobotNodePtr EndEffector::getTcp() @@ -650,14 +650,14 @@ namespace VirtualRobot ss << "gcp='" << gcpNode->getName() << "' "; } - ss << ">" << endl; + ss << ">" << std::endl; // Preshapes std::map< std::string, RobotConfigPtr >::iterator itPre = preshapes.begin(); while (itPre != preshapes.end()) { - ss << tt << "<Preshape name='" << itPre->first << "'>" << endl; + ss << tt << "<Preshape name='" << itPre->first << "'>" << std::endl; std::map < std::string, float > jv = itPre->second->getRobotNodeJointValueMap(); std::map< std::string, float >::const_iterator i = jv.begin(); @@ -668,21 +668,21 @@ namespace VirtualRobot i++; } - ss << tt << "</Preshape>" << endl; + ss << tt << "</Preshape>" << std::endl; itPre++; } // Static if (statics.size() > 0) { - ss << tt << "<Static>" << endl; + ss << tt << "<Static>" << std::endl; for (auto& i : statics) { - ss << ttt << "<Node name='" << i->getName() << "'/>" << endl; + ss << ttt << "<Node name='" << i->getName() << "'/>" << std::endl; } - ss << tt << "</Static>" << endl; + ss << tt << "</Static>" << std::endl; } // Actors @@ -691,7 +691,7 @@ namespace VirtualRobot ss << actor->toXML(ident + 1); } - ss << pre << "</EndEffector>" << endl; + ss << pre << "</EndEffector>" << std::endl; return ss.str(); } @@ -714,7 +714,7 @@ namespace VirtualRobot int id1, id2; Eigen::Vector3f p1, p2; float dist = this->getCollisionChecker()->calculateDistance(n->getCollisionModel(), obstacle->getCollisionModel(), p1, p2, &id1, &id2); - //VR_INFO << n->getName() << " - DIST: " << dist << endl; + //VR_INFO << n->getName() << " - DIST: " << dist << std::endl; if (dist <= maxDistance) { EndEffector::ContactInfo ci; diff --git a/VirtualRobot/EndEffector/EndEffectorActor.cpp b/VirtualRobot/EndEffector/EndEffectorActor.cpp index 02499d5a86532f845e4f6ba3becace876046ce34..8601d6312f4708f121c4f3075b303b7725f921d1 100644 --- a/VirtualRobot/EndEffector/EndEffectorActor.cpp +++ b/VirtualRobot/EndEffector/EndEffectorActor.cpp @@ -431,16 +431,16 @@ namespace VirtualRobot void EndEffectorActor::print() { - cout << " ****" << endl; - cout << " ** Name:" << name << endl; + std::cout << " ****" << std::endl; + std::cout << " ** Name:" << name << std::endl; for (auto& actor : actors) { - cout << " *** RobotNode: " << actor.robotNode->getName() << ", Direction/Speed:" << actor.directionAndSpeed << endl; + std::cout << " *** RobotNode: " << actor.robotNode->getName() << ", Direction/Speed:" << actor.directionAndSpeed << std::endl; //actors[i].robotNode->print(); } - cout << " ****" << endl; + std::cout << " ****" << std::endl; } bool EndEffectorActor::hasNode(RobotNodePtr node) @@ -543,7 +543,7 @@ namespace VirtualRobot std::string tt = pre + t; std::string ttt = tt + t; - ss << pre << "<Actor name='" << name << "'>" << endl; + ss << pre << "<Actor name='" << name << "'>" << std::endl; for (auto& actor : actors) { @@ -571,10 +571,10 @@ namespace VirtualRobot } } - ss << "Direction='" << actor.directionAndSpeed << "'/>" << endl; + ss << "Direction='" << actor.directionAndSpeed << "'/>" << std::endl; } - ss << pre << "</Actor>" << endl; + ss << pre << "</Actor>" << std::endl; return ss.str(); } diff --git a/VirtualRobot/Grasping/BasicGraspQualityMeasure.cpp b/VirtualRobot/Grasping/BasicGraspQualityMeasure.cpp index 8abfe98865592242e4a343397ce49746e3ce9c51..c43bcc96c167405a0478b9083017239263cabbfd 100644 --- a/VirtualRobot/Grasping/BasicGraspQualityMeasure.cpp +++ b/VirtualRobot/Grasping/BasicGraspQualityMeasure.cpp @@ -90,7 +90,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << ": Nr of contact points:" << this->contactPoints.size() << endl; + VR_INFO << ": Nr of contact points:" << this->contactPoints.size() << std::endl; } } @@ -130,7 +130,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << ": Nr of contact points:" << this->contactPoints.size() << endl; + VR_INFO << ": Nr of contact points:" << this->contactPoints.size() << std::endl; } } diff --git a/VirtualRobot/Grasping/Grasp.cpp b/VirtualRobot/Grasping/Grasp.cpp index 2566b9b4de9e8b2fde6aedef1d20d9078248be88..22738b27bc7c482b76107dd05a12e2afd62f4daf 100644 --- a/VirtualRobot/Grasping/Grasp.cpp +++ b/VirtualRobot/Grasping/Grasp.cpp @@ -28,26 +28,26 @@ namespace VirtualRobot { if (printDecoration) { - cout << "**** Grasp ****" << endl; - cout << " * Robot type: " << robotType << endl; - cout << " * End Effector: " << eef << endl; - cout << " * EEF Preshape: " << preshape << endl; + std::cout << "**** Grasp ****" << std::endl; + std::cout << " * Robot type: " << robotType << std::endl; + std::cout << " * End Effector: " << eef << std::endl; + std::cout << " * EEF Preshape: " << preshape << std::endl; } - cout << " * Name: " << name << endl; - cout << " * Creation Method: " << creation << endl; - cout << " * Quality: " << quality << endl; + std::cout << " * Name: " << name << std::endl; + std::cout << " * Creation Method: " << creation << std::endl; + std::cout << " * Quality: " << quality << std::endl; { // scope std::ostringstream sos; sos << std::setiosflags(std::ios::fixed); - sos << " * Pose in EEF-TCP coordinate system:" << endl << poseTcp << endl; - cout << sos.str() << endl; + sos << " * Pose in EEF-TCP coordinate system:" << endl << poseTcp << std::endl; + std::cout << sos.str() << std::endl; } // scope if (printDecoration) { - cout << endl; + std::cout << std::endl; } } @@ -69,7 +69,7 @@ namespace VirtualRobot if (!eefPtr) { - VR_ERROR << "No EndEffector with name " << eef << " stored in robot " << robot->getName() << endl; + VR_ERROR << "No EndEffector with name " << eef << " stored in robot " << robot->getName() << std::endl; return Eigen::Matrix4f::Identity(); } @@ -77,7 +77,7 @@ namespace VirtualRobot if (!tcpNode) { - VR_ERROR << "No tcp with name " << eefPtr->getTcpName() << " in EndEffector " << eef << " in robot " << robot->getName() << endl; + VR_ERROR << "No tcp with name " << eefPtr->getTcpName() << " in EndEffector " << eef << " in robot " << robot->getName() << std::endl; return Eigen::Matrix4f::Identity(); } diff --git a/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp b/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp index 9a597b05b9f9ebdeebb4ae8214dc35bd2f0b06dc..e5d76169eabb61ece11a12014619f6f243c7869b 100644 --- a/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp +++ b/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp @@ -42,7 +42,7 @@ namespace VirtualRobot bool embeddedGraspEditor) : QMainWindow(nullptr), UI(new Ui::MainWindowGraspEditor) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; // Indicates whether this program is started inside another extern program this->embeddedGraspEditor = embeddedGraspEditor; @@ -83,10 +83,10 @@ namespace VirtualRobot SphereApproximatorPtr sa(new SphereApproximator()); SphereApproximator::SphereApproximation app; sa->generateGraph(app, SphereApproximator::eIcosahedron, 3, 200.0f); - cout << "nr faces:" << app.faces.size() << ", vert:" << app.vertices.size() << endl; + std::cout << "nr faces:" << app.faces.size() << ", vert:" << app.vertices.size() << std::endl; TriMeshModelPtr tri = sa->generateTriMesh(app); - cout << "2 nr faces:" << tri->faces.size() << ", vert:" << tri->vertices.size() << endl; + std::cout << "2 nr faces:" << tri->faces.size() << ", vert:" << tri->vertices.size() << std::endl; SoNode* m = CoinVisualizationFactory::getCoinVisualization(tri, true); sceneSep->addChild(m); @@ -414,21 +414,21 @@ namespace VirtualRobot } catch (VirtualRobotException& e) { - cout << " ERROR while saving object" << endl; - cout << e.what(); + std::cout << " ERROR while saving object" << std::endl; + std::cout << e.what(); return; } if (!ok) { - cout << " ERROR while saving object" << endl; + std::cout << " ERROR while saving object" << std::endl; return; } else { if (embeddedGraspEditor) { - cout << "Changes successful saved to " << objectFile << endl; + std::cout << "Changes successful saved to " << objectFile << std::endl; QMessageBox msgBox; msgBox.setText(QString::fromStdString("Changes successful saved to " + objectFile)); msgBox.setIcon(QMessageBox::Information); @@ -442,7 +442,7 @@ namespace VirtualRobot void GraspEditorWindow::loadRobot() { robotSep->removeAllChildren(); - cout << "Loading Robot from " << robotFile << endl; + std::cout << "Loading Robot from " << robotFile << std::endl; try { @@ -450,14 +450,14 @@ namespace VirtualRobot } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return; } @@ -564,7 +564,7 @@ namespace VirtualRobot void GraspEditorWindow::loadObject() { objectSep->removeAllChildren(); - cout << "Loading Object from " << objectFile << endl; + std::cout << "Loading Object from " << objectFile << std::endl; try { @@ -572,8 +572,8 @@ namespace VirtualRobot } catch (VirtualRobotException& e) { - cout << " ERROR while creating object" << endl; - cout << e.what(); + std::cout << " ERROR while creating object" << std::endl; + std::cout << e.what(); if (embeddedGraspEditor) { @@ -591,7 +591,7 @@ namespace VirtualRobot if (!object) { - cout << " ERROR while creating object" << endl; + std::cout << " ERROR while creating object" << std::endl; return; } @@ -697,13 +697,13 @@ namespace VirtualRobot { if (robotEEF) { - //cout << "getGlobalPose robot:" << endl << robotEEF->getGlobalPose() << endl; - //cout << "getGlobalPose TCP:" << endl << robotEEF_EEF->getTcp()->getGlobalPose() << endl; + //cout << "getGlobalPose robot:" << endl << robotEEF->getGlobalPose() << std::endl; + //cout << "getGlobalPose TCP:" << endl << robotEEF_EEF->getTcp()->getGlobalPose() << std::endl; Eigen::Matrix4f m; MathTools::posrpy2eigen4f(x, m); RobotNodePtr tcp = robotEEF_EEF->getTcp(); m = tcp->getGlobalPose() * m; - //cout << "pose:" << endl << m << endl; + //cout << "pose:" << endl << m << std::endl; setCurrentGrasp(m); } diff --git a/VirtualRobot/Grasping/GraspSet.cpp b/VirtualRobot/Grasping/GraspSet.cpp index 3b18a40359221570203e3f5f29f88ef7b148057e..7d9b3d6cf83e4a0d68646346327e323565190d10 100644 --- a/VirtualRobot/Grasping/GraspSet.cpp +++ b/VirtualRobot/Grasping/GraspSet.cpp @@ -78,19 +78,19 @@ namespace VirtualRobot void GraspSet::print() const { - cout << "**** Grasp set ****" << endl; - cout << "Name: " << name << endl; - cout << "Robot Type: " << robotType << endl; - cout << "End Effector: " << eef << endl; - cout << "Grasps:" << endl; + std::cout << "**** Grasp set ****" << std::endl; + std::cout << "Name: " << name << std::endl; + std::cout << "Robot Type: " << robotType << std::endl; + std::cout << "End Effector: " << eef << std::endl; + std::cout << "Grasps:" << std::endl; for (size_t i = 0; i < grasps.size(); i++) { - cout << "** grasp " << i << ":" << endl; + std::cout << "** grasp " << i << ":" << std::endl; grasps[i]->print(false); } - cout << endl; + std::cout << std::endl; } bool GraspSet::isCompatibleGrasp(GraspPtr grasp) const diff --git a/VirtualRobot/IK/AdvancedIKSolver.cpp b/VirtualRobot/IK/AdvancedIKSolver.cpp index fecb0ee8759bddbc656ebfdeceb12d3ee1d492f6..a352d6c50a96ed8ea4c1adad7d1c0c993d002eeb 100644 --- a/VirtualRobot/IK/AdvancedIKSolver.cpp +++ b/VirtualRobot/IK/AdvancedIKSolver.cpp @@ -112,7 +112,7 @@ namespace VirtualRobot { if (eef) { - VR_ERROR << " Two end effectors with tcp " << rns->getTCP()->getName() << " defined in robot " << robot->getName() << ". taking the first one?!" << endl; + VR_ERROR << " Two end effectors with tcp " << rns->getTCP()->getName() << " defined in robot " << robot->getName() << ". taking the first one?!" << std::endl; } else { @@ -123,7 +123,7 @@ namespace VirtualRobot if (!eef) { - VR_ERROR << " No end effector with tcp " << rns->getTCP()->getName() << " defined in robot " << robot->getName() << ". Aborting..." << endl; + VR_ERROR << " No end effector with tcp " << rns->getTCP()->getName() << " defined in robot " << robot->getName() << ". Aborting..." << std::endl; return GraspPtr(); } @@ -131,7 +131,7 @@ namespace VirtualRobot if (!gs || gs->getSize() == 0) { - VR_ERROR << " No grasps defined for eef " << eef->getName() << " defined in object " << object->getName() << ". Aborting..." << endl; + VR_ERROR << " No grasps defined for eef " << eef->getName() << " defined in object " << object->getName() << ". Aborting..." << std::endl; return GraspPtr(); } @@ -237,12 +237,12 @@ namespace VirtualRobot { if (reachabilitySpace->getTCP() != tcp) { - VR_ERROR << "Reachability representation has different tcp RobotNode (" << reachabilitySpace->getTCP()->getName() << ") than IK solver (" << tcp->getName() << ") ?! " << endl << "Reachability results may not be valid!" << endl; + VR_ERROR << "Reachability representation has different tcp RobotNode (" << reachabilitySpace->getTCP()->getName() << ") than IK solver (" << tcp->getName() << ") ?! " << endl << "Reachability results may not be valid!" << std::endl; } if (reachabilitySpace->getNodeSet() != rns) { - VR_ERROR << "Reachability representation is defined for a different RobotNodeSet (" << reachabilitySpace->getNodeSet()->getName() << ") than IK solver uses (" << rns->getName() << ") ?! " << endl << "Reachability results may not be valid!" << endl; + VR_ERROR << "Reachability representation is defined for a different RobotNodeSet (" << reachabilitySpace->getNodeSet()->getName() << ") than IK solver uses (" << rns->getName() << ") ?! " << endl << "Reachability results may not be valid!" << std::endl; } } } diff --git a/VirtualRobot/IK/CoMIK.cpp b/VirtualRobot/IK/CoMIK.cpp index 85d80e7f7319e82d8a8ebe00ef2083faabbcccb3..cff8eeffac7583f60c3d601bfd5dbaf4f3426538 100644 --- a/VirtualRobot/IK/CoMIK.cpp +++ b/VirtualRobot/IK/CoMIK.cpp @@ -40,7 +40,7 @@ namespace VirtualRobot if (rnsBodies->getMass() == 0) { - VR_ERROR << "The RNS does not contain any bodies or masses are not specified (mass==0)" << endl; + VR_ERROR << "The RNS does not contain any bodies or masses are not specified (mass==0)" << std::endl; } } @@ -115,7 +115,7 @@ namespace VirtualRobot } else if (target.rows() == 1) { - VR_INFO << "One dimensional CoMs not supported." << endl; + VR_INFO << "One dimensional CoMs not supported." << std::endl; } return position; @@ -205,7 +205,7 @@ namespace VirtualRobot // Check for singularities if (!isValid(dTheta)) { - VR_INFO << "Singular Jacobian" << endl; + VR_INFO << "Singular Jacobian" << std::endl; return false; } @@ -220,7 +220,7 @@ namespace VirtualRobot // check tolerances if (checkTolerances()) { - VR_INFO << "Tolerances ok, loop:" << step << endl; + VR_INFO << "Tolerances ok, loop:" << step << std::endl; return true; } @@ -228,13 +228,13 @@ namespace VirtualRobot if (dTheta.norm() < minumChange) { - VR_INFO << "Could not improve result any more (dTheta.norm()=" << d << "), loop:" << step << endl; + VR_INFO << "Could not improve result any more (dTheta.norm()=" << d << "), loop:" << step << std::endl; return false; } if (checkImprovement && d > lastDist) { - VR_INFO << "Could not improve result any more (dTheta.norm()=" << d << ", last loop's norm:" << lastDist << "), loop:" << step << endl; + VR_INFO << "Could not improve result any more (dTheta.norm()=" << d << ", last loop's norm:" << lastDist << "), loop:" << step << std::endl; return false; } @@ -243,8 +243,8 @@ namespace VirtualRobot } #ifndef NO_FAILURE_OUTPUT - //VR_INFO << "IK failed, loop:" << step << endl; - //VR_INFO << "error:" << (target - rns->getCoM().head(target.rows())).norm() << endl; + //VR_INFO << "IK failed, loop:" << step << std::endl; + //VR_INFO << "error:" << (target - rns->getCoM().head(target.rows())).norm() << std::endl; #endif return false; } @@ -260,18 +260,18 @@ namespace VirtualRobot if (coordSystem) { - cout << "Coordsystem: " << coordSystem->getName() << endl; + std::cout << "Coordsystem: " << coordSystem->getName() << std::endl; } else { - cout << "Coordsystem: global" << endl; + std::cout << "Coordsystem: global" << std::endl; } - cout << "Target:" << endl << this->target.transpose() << endl; - cout << "Tolerances pos: " << this->tolerance << endl; - cout << "RNS bodies:" << rnsBodies->getName() << endl; - cout << "CoM:" << rnsBodies->getCoM().head(target.rows()).transpose() << endl; - cout << "Error:" << endl << getError().transpose() << endl; + std::cout << "Target:" << endl << this->target.transpose() << std::endl; + std::cout << "Tolerances pos: " << this->tolerance << std::endl; + std::cout << "RNS bodies:" << rnsBodies->getName() << std::endl; + std::cout << "CoM:" << rnsBodies->getCoM().head(target.rows()).transpose() << std::endl; + std::cout << "Error:" << endl << getError().transpose() << std::endl; } } diff --git a/VirtualRobot/IK/DifferentialIK.cpp b/VirtualRobot/IK/DifferentialIK.cpp index af52842fd5ec30d279319ccdc446b881072eb213..87c008399e7475bb687729173529c8af5304c805 100644 --- a/VirtualRobot/IK/DifferentialIK.cpp +++ b/VirtualRobot/IK/DifferentialIK.cpp @@ -73,7 +73,7 @@ namespace VirtualRobot { if (!tcp->getParent()) { - VR_ERROR << "tcp not linked to a parent!!!" << endl; + VR_ERROR << "tcp not linked to a parent!!!" << std::endl; return; } @@ -81,7 +81,7 @@ namespace VirtualRobot if (!tcpRN) { - VR_ERROR << "tcp not linked to robotNode!!!" << endl; + VR_ERROR << "tcp not linked to robotNode!!!" << std::endl; return; } } @@ -158,7 +158,7 @@ namespace VirtualRobot } else { - VR_ERROR << "Internal error?!" << endl; // Error + VR_ERROR << "Internal error?!" << std::endl; // Error } } } @@ -233,7 +233,7 @@ namespace VirtualRobot } else { - VR_ERROR << "Internal error?!" << endl; // Error + VR_ERROR << "Internal error?!" << std::endl; // Error } } } @@ -340,7 +340,7 @@ namespace VirtualRobot { if (!tcp->getParent()) { - VR_ERROR << "tcp not linked to a parent!!!" << endl; + VR_ERROR << "tcp not linked to a parent!!!" << std::endl; jac.setZero(); return; } @@ -349,7 +349,7 @@ namespace VirtualRobot if (!tcpRN) { - VR_ERROR << "tcp not linked to robotNode!!!" << endl; + VR_ERROR << "tcp not linked to robotNode!!!" << std::endl; jac.setZero(); return; } @@ -413,8 +413,8 @@ namespace VirtualRobot toTCP /= 1000.0f; } - //cout << "toTCP: " << tcp->getName() << endl; - //cout << toTCP << endl; + //cout << "toTCP: " << tcp->getName() << std::endl; + //cout << toTCP << std::endl; tmpUpdateJacobianPosition.block(0, i, 3, 1) = axis.cross(toTCP); } @@ -451,7 +451,7 @@ namespace VirtualRobot if (diffClock > 0.0f) { - cout << "Jacobi Loop " << i << ": RobotNode: " << dof->getName() << ", time:" << diffClock << endl; + std::cout << "Jacobi Loop " << i << ": RobotNode: " << dof->getName() << ", time:" << diffClock << std::endl; } #endif @@ -489,8 +489,8 @@ namespace VirtualRobot jac.block(index, 0, 3, nDoF) = tmpUpdateJacobianOrientation; } - //cout << "partial JACOBIAN: (row 1-3)" << endl; - //cout << result.block(0,0,3,3) << endl; + //cout << "partial JACOBIAN: (row 1-3)" << std::endl; + //cout << result.block(0,0,3,3) << std::endl; #ifdef CHECK_PERFORMANCE clock_t endT = clock(); @@ -498,7 +498,7 @@ namespace VirtualRobot if (diffClock > 1.0f) { - cout << "Jacobirest time:" << diffClock << endl; + std::cout << "Jacobirest time:" << diffClock << std::endl; } #endif @@ -536,7 +536,7 @@ namespace VirtualRobot clock_t endT = clock(); float diffClock1 = (float)(((float)(startT2 - startT) / (float)CLOCKS_PER_SEC) * 1000.0f); float diffClock2 = (float)(((float)(endT - startT2) / (float)CLOCKS_PER_SEC) * 1000.0f); - cout << "getPseudoInverseJacobianMatrix time1:" << diffClock1 << ", time2: " << diffClock2 << endl; + std::cout << "getPseudoInverseJacobianMatrix time1:" << diffClock1 << ", time2: " << diffClock2 << std::endl; #endif return res; } @@ -603,14 +603,14 @@ namespace VirtualRobot if (coordSystem) { - cout << "Coordsystem: " << coordSystem->getName() << endl; + std::cout << "Coordsystem: " << coordSystem->getName() << std::endl; } else { - cout << "Coordsystem: global" << endl; + std::cout << "Coordsystem: global" << std::endl; } - cout << "TCPs:" << endl; + std::cout << "TCPs:" << std::endl; for (auto tcp : tcp_set) { @@ -621,30 +621,30 @@ namespace VirtualRobot continue; } - cout << "* " << tcpRN->getName() << endl; - cout << "** Target: " << endl << this->targets[tcp] << endl; - cout << "** Error: " << getDeltaToGoal(tcp).transpose() << endl; - cout << "** mode:"; + std::cout << "* " << tcpRN->getName() << std::endl; + std::cout << "** Target: " << endl << this->targets[tcp] << std::endl; + std::cout << "** Error: " << getDeltaToGoal(tcp).transpose() << std::endl; + std::cout << "** mode:"; if (this->modes[tcp] == IKSolver::All) { - cout << "all" << endl; + std::cout << "all" << std::endl; } else if (this->modes[tcp] == IKSolver::Position) { - cout << "position" << endl; + std::cout << "position" << std::endl; } else if (this->modes[tcp] == IKSolver::Orientation) { - cout << "orientation" << endl; + std::cout << "orientation" << std::endl; } else { - cout << "unknown" << endl; + std::cout << "unknown" << std::endl; } - cout << "** tolerances pos: " << this->tolerancePosition[tcp] << ", rot:" << this->toleranceRotation[tcp] << endl; - cout << "** Nodes:"; + std::cout << "** tolerances pos: " << this->tolerancePosition[tcp] << ", rot:" << this->toleranceRotation[tcp] << std::endl; + std::cout << "** Nodes:"; // Iterate over all degrees of freedom for (size_t i = 0; i < nDoF; i++) @@ -654,11 +654,11 @@ namespace VirtualRobot //check if the tcp is affected by this DOF if (find(parents[tcpRN].begin(), parents[tcpRN].end(), dof) != parents[tcpRN].end()) { - cout << dof->getName() << ","; + std::cout << dof->getName() << ","; } } - cout << endl; + std::cout << std::endl; } } @@ -760,10 +760,10 @@ namespace VirtualRobot }*/ if (verbose) { - VR_INFO << "ERROR (TASK):" << endl << currentError << endl; - VR_INFO << "JACOBIAN:" << endl << currentJacobian << endl; - VR_INFO << "PSEUDOINVERSE JACOBIAN:" << endl << currentInvJacobian << endl; - VR_INFO << "THETA (JOINT):" << endl << tmpComputeStepTheta << endl; + VR_INFO << "ERROR (TASK):" << endl << currentError << std::endl; + VR_INFO << "JACOBIAN:" << endl << currentJacobian << std::endl; + VR_INFO << "PSEUDOINVERSE JACOBIAN:" << endl << currentInvJacobian << std::endl; + VR_INFO << "THETA (JOINT):" << endl << tmpComputeStepTheta << std::endl; } return tmpComputeStepTheta; @@ -850,7 +850,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "TCP " << tcp->getName() << ", errPos:" << currentErrorPos << ", errRot:" << currentErrorRot << ", maxErrPos:" << maxErrorPos << ", maxErrorRot:" << maxErrorRot << endl; + VR_INFO << "TCP " << tcp->getName() << ", errPos:" << currentErrorPos << ", errRot:" << currentErrorRot << ", maxErrPos:" << maxErrorPos << ", maxErrorRot:" << maxErrorRot << std::endl; } if (currentErrorPos > maxErrorPos || currentErrorRot > maxErrorRot) @@ -892,7 +892,7 @@ namespace VirtualRobot if (boost::math::isnan(jv[i]) || boost::math::isinf(jv[i])) { - VR_WARNING << "Aborting, invalid joint value (nan)" << endl; + VR_WARNING << "Aborting, invalid joint value (nan)" << std::endl; return false; } } @@ -904,7 +904,7 @@ namespace VirtualRobot { if (verbose) { - VR_INFO << "Tolerances ok, loop:" << step << endl; + VR_INFO << "Tolerances ok, loop:" << step << std::endl; } return true; @@ -916,7 +916,7 @@ namespace VirtualRobot { if (verbose) { - VR_INFO << "Could not improve result any more (dTheta.norm()=" << d << "), loop:" << step << endl; + VR_INFO << "Could not improve result any more (dTheta.norm()=" << d << "), loop:" << step << std::endl; } robot->setJointValues(rns, jvBest); @@ -929,7 +929,7 @@ namespace VirtualRobot { if (verbose) { - VR_INFO << "Could not improve result any more (current position error=" << posDist << ", last loop's error:" << lastDist << "), loop:" << step << endl; + VR_INFO << "Could not improve result any more (current position error=" << posDist << ", last loop's error:" << lastDist << "), loop:" << step << std::endl; } robot->setJointValues(rns, jvBest); @@ -943,9 +943,9 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "IK failed, loop:" << step << endl; - VR_INFO << "pos error:" << getErrorPosition() << endl; - VR_INFO << "rot error:" << getErrorRotation() << endl; + VR_INFO << "IK failed, loop:" << step << std::endl; + VR_INFO << "pos error:" << getErrorPosition() << std::endl; + VR_INFO << "rot error:" << getErrorRotation() << std::endl; } robot->setJointValues(rns, jvBest); diff --git a/VirtualRobot/IK/FeetPosture.cpp b/VirtualRobot/IK/FeetPosture.cpp index 9d657f6b4810b9060c706fb4a364d877d564fedf..5bd0fdaccc0e7d84aa504544336a50a0c71d3fcd 100644 --- a/VirtualRobot/IK/FeetPosture.cpp +++ b/VirtualRobot/IK/FeetPosture.cpp @@ -81,22 +81,22 @@ namespace VirtualRobot void FeetPosture::print() { - cout << "FeetPosture:" << endl; - cout << "* Left leg:" << leftLeg->getName() << endl; - cout << "* Left leg collision model:" << leftLegCol->getName() << endl; - cout << "* Left Foot/TCP:" << leftTCP->getName() << endl; - cout << "* Right leg:" << rightLeg->getName() << endl; - cout << "* Right leg collision model:" << rightLegCol->getName() << endl; - cout << "* Right Foot/TCP:" << rightTCP->getName() << endl; - cout << "* Base Node: " << baseNode->getName() << endl; + std::cout << "FeetPosture:" << std::endl; + std::cout << "* Left leg:" << leftLeg->getName() << std::endl; + std::cout << "* Left leg collision model:" << leftLegCol->getName() << std::endl; + std::cout << "* Left Foot/TCP:" << leftTCP->getName() << std::endl; + std::cout << "* Right leg:" << rightLeg->getName() << std::endl; + std::cout << "* Right leg collision model:" << rightLegCol->getName() << std::endl; + std::cout << "* Right Foot/TCP:" << rightTCP->getName() << std::endl; + std::cout << "* Base Node: " << baseNode->getName() << std::endl; if (left2Right) { - cout << "* RNS Left->Right foot: " << left2Right->getName() << endl; + std::cout << "* RNS Left->Right foot: " << left2Right->getName() << std::endl; } else { - cout << "* RNS Left->Right foot: <not set>" << endl; + std::cout << "* RNS Left->Right foot: <not set>" << std::endl; } } diff --git a/VirtualRobot/IK/GazeIK.cpp b/VirtualRobot/IK/GazeIK.cpp index dcf833bb5ad6cfc2a9b0d6a58d07b5c2b99a9e4a..4d69203ae4611ae8182b5e18660394e09e05bacd 100644 --- a/VirtualRobot/IK/GazeIK.cpp +++ b/VirtualRobot/IK/GazeIK.cpp @@ -102,7 +102,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "ikGaze delta:\n" << deltaGaze.head(3) << endl; + VR_INFO << "ikGaze delta:\n" << deltaGaze.head(3) << std::endl; } jacobies.push_back(ikGaze); @@ -132,7 +132,7 @@ namespace VirtualRobot // initialize the virtualGazeJoint with a guess float v = (goal - virtualTranslationJoint->getParent()->getGlobalPose().block(0, 3, 3, 1)).norm(); virtualTranslationJoint->setJointValue(v); - //VR_INFO << "virtualTranslationJoint jv:" << v << endl; + //VR_INFO << "virtualTranslationJoint jv:" << v << std::endl; // first run: start with current joint angles @@ -141,7 +141,7 @@ namespace VirtualRobot return true; } - VR_INFO << "No solution from current configuration, trying with random seeded configuration" << endl; + VR_INFO << "No solution from current configuration, trying with random seeded configuration" << std::endl; float posDist = getCurrentError(goal); jvBest = rns->getJointValues(); @@ -150,20 +150,20 @@ namespace VirtualRobot // if here we failed for (int i = 1; i < maxLoops; i++) { - //VR_INFO << "loop " << i << endl; + //VR_INFO << "loop " << i << std::endl; // set rotational joints randomly setJointsRandom(goal, randomTriesToGetBestConfig); // update translational joint with initial guess float v = (goal - virtualTranslationJoint->getParent()->getGlobalPose().block(0, 3, 3, 1)).norm(); virtualTranslationJoint->setJointValue(v); - //VR_INFO << "virtualTranslationJoint jv:" << v << endl; + //VR_INFO << "virtualTranslationJoint jv:" << v << std::endl; // check if there is a gradient to the solution if (trySolve(goal, stepSize)) { - //VR_INFO << "Solution found " << endl; + //VR_INFO << "Solution found " << std::endl; return true; } @@ -171,13 +171,13 @@ namespace VirtualRobot if (posDist < bestDist) { - //VR_INFO << "New best solution, dist:" << posDist << endl; + //VR_INFO << "New best solution, dist:" << posDist << std::endl; jvBest = rns->getJointValues(); bestDist = posDist; } } - VR_INFO << "Setting joint values ot best achieved config, dist to target:" << bestDist << endl; + VR_INFO << "Setting joint values ot best achieved config, dist to target:" << bestDist << std::endl; rns->setJointValues(jvBest); return false; @@ -202,7 +202,7 @@ namespace VirtualRobot if (posDist < bestDist) { - //VR_INFO << "joints random, best dist:" << posDist << endl; + //VR_INFO << "joints random, best dist:" << posDist << std::endl; bestDist = posDist; jvBest = rns->getJointValues(); } @@ -266,7 +266,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "applyJLA step " << step << ", theta:" << dTheta.transpose() << endl; + VR_INFO << "applyJLA step " << step << ", theta:" << dTheta.transpose() << std::endl; } @@ -278,7 +278,7 @@ namespace VirtualRobot if (boost::math::isnan(jv[i]) || boost::math::isinf(jv[i])) { rns->setJointValues(jvBest); - VR_WARNING << "Aborting, invalid joint value (nan)" << endl; + VR_WARNING << "Aborting, invalid joint value (nan)" << std::endl; return; } } @@ -298,7 +298,7 @@ namespace VirtualRobot { if (verbose) { - VR_INFO << "Could not improve result any more with joint limit avoidance tasks (dTheta.norm()=" << d << "), loop:" << step << endl; + VR_INFO << "Could not improve result any more with joint limit avoidance tasks (dTheta.norm()=" << d << "), loop:" << step << std::endl; } return; @@ -328,7 +328,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "step " << step << ", theta:" << dTheta.transpose() << endl; + VR_INFO << "step " << step << ", theta:" << dTheta.transpose() << std::endl; } for (unsigned int i = 0; i < nodes.size(); i++) @@ -338,7 +338,7 @@ namespace VirtualRobot // sanity check if (boost::math::isnan(jv[i]) || boost::math::isinf(jv[i])) { - VR_WARNING << "Aborting, invalid joint value (nan)" << endl; + VR_WARNING << "Aborting, invalid joint value (nan)" << std::endl; return false; } } @@ -350,7 +350,7 @@ namespace VirtualRobot { if (verbose) { - VR_INFO << "Tolerances ok, loop:" << step << endl; + VR_INFO << "Tolerances ok, loop:" << step << std::endl; } // try to improve pose by applying some joint limit avoidance steps @@ -362,7 +362,7 @@ namespace VirtualRobot if (checkImprovement && posDist>lastDist) { if (verbose) - VR_INFO << "Could not improve result any more (current position error=" << posDist << ", last loop's error:" << lastDist << "), loop:" << step << endl; + VR_INFO << "Could not improve result any more (current position error=" << posDist << ", last loop's error:" << lastDist << "), loop:" << step << std::endl; robot->setJointValues(rns,jvBest); return false; }*/ @@ -373,7 +373,7 @@ namespace VirtualRobot { if (verbose) { - VR_INFO << "Could not improve result any more (dTheta.norm()=" << d << "), loop:" << step << endl; + VR_INFO << "Could not improve result any more (dTheta.norm()=" << d << "), loop:" << step << std::endl; } return false; @@ -392,8 +392,8 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "IK failed, loop:" << step << endl; - VR_INFO << "pos error:" << getCurrentError(goal) << endl; + VR_INFO << "IK failed, loop:" << step << std::endl; + VR_INFO << "pos error:" << getCurrentError(goal) << std::endl; } robot->setJointValues(rns, jvBest); diff --git a/VirtualRobot/IK/HierarchicalIK.cpp b/VirtualRobot/IK/HierarchicalIK.cpp index 2f7405b515afa01d7eef5cada393d7a869f58360..049cbdfa07cb356631c159a28a040c56d3d28592 100644 --- a/VirtualRobot/IK/HierarchicalIK.cpp +++ b/VirtualRobot/IK/HierarchicalIK.cpp @@ -33,7 +33,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "Compute Step" << endl; + VR_INFO << "Compute Step" << std::endl; } int ndof = jacDefs[0]->getRobotNodeSet()->getSize(); @@ -51,7 +51,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "Jacoby " << i << ":\n" << j << endl; + VR_INFO << "Jacoby " << i << ":\n" << j << std::endl; } j = jacDefs[i]->computePseudoInverseJacobianMatrixD(j);// jacDefs[i].tcp); @@ -61,7 +61,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "Inv Jacoby " << i << ":\n" << j << endl; + VR_INFO << "Inv Jacoby " << i << ":\n" << j << std::endl; } if (jacobies[i].cols() != ndof) @@ -87,7 +87,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "result_i 0:\n" << result_i << endl; + VR_INFO << "result_i 0:\n" << result_i << std::endl; } Eigen::VectorXd result_i_min1; @@ -119,7 +119,7 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "JA_i_min1 " << i << ":\n" << endl << JA_i_min1 << endl; + VR_INFO << "JA_i_min1 " << i << ":\n" << endl << JA_i_min1 << std::endl; } switch (method) @@ -141,21 +141,21 @@ namespace VirtualRobot //JAinv_i_min1 = MathTools::getPseudoInverse(JA_i_min1, pinvtoler); if (verbose) { - VR_INFO << "JAinv_i_min1 " << i << ":\n" << endl << JAinv_i_min1 << endl; + VR_INFO << "JAinv_i_min1 " << i << ":\n" << endl << JAinv_i_min1 << std::endl; } PA_i_min1 = id_ndof - JAinv_i_min1 * JA_i_min1; if (verbose) { - VR_INFO << "PA_i_min1 " << i << ":\n" << endl << PA_i_min1 << endl; + VR_INFO << "PA_i_min1 " << i << ":\n" << endl << PA_i_min1 << std::endl; } Eigen::MatrixXd J_tilde_i = J_i * PA_i_min1; if (verbose) { - VR_INFO << "J_tilde_i " << i << ":\n" << endl << J_tilde_i << endl; + VR_INFO << "J_tilde_i " << i << ":\n" << endl << J_tilde_i << std::endl; } Eigen::MatrixXd Jinv_tilde_i; @@ -179,19 +179,19 @@ namespace VirtualRobot if (verbose) { - VR_INFO << "Jinv_tilde_i " << i << ":\n" << endl << Jinv_tilde_i << endl; + VR_INFO << "Jinv_tilde_i " << i << ":\n" << endl << Jinv_tilde_i << std::endl; } if (verbose) { - VR_INFO << "jacDefs[i]->getError() " << i << ":\n" << endl << errors[i].transpose() << endl; + VR_INFO << "jacDefs[i]->getError() " << i << ":\n" << endl << errors[i].transpose() << std::endl; } result_i = result_i_min1 + Jinv_tilde_i * (errors[i] * stepSize - J_i * result_i_min1); if (verbose) { - VR_INFO << "result_i " << i << ":\n" << result_i << endl; + VR_INFO << "result_i " << i << ":\n" << result_i << std::endl; } accRowCount += J_i.rows(); diff --git a/VirtualRobot/IK/HierarchicalIKSolver.cpp b/VirtualRobot/IK/HierarchicalIKSolver.cpp index b9864223980eaa83b366e9cd248e7fa6ed29b690..a62d0d8b806322922c56e8a4fc1419760cde0e06 100644 --- a/VirtualRobot/IK/HierarchicalIKSolver.cpp +++ b/VirtualRobot/IK/HierarchicalIKSolver.cpp @@ -30,7 +30,7 @@ bool HierarchicalIKSolver::computeSteps(float stepSize, float minChange, int max if (!MathTools::isValid(delta)) { #ifdef DEBUG - VR_INFO << "Singular Jacobian" << endl; + VR_INFO << "Singular Jacobian" << std::endl; #endif return false; } @@ -43,7 +43,7 @@ bool HierarchicalIKSolver::computeSteps(float stepSize, float minChange, int max if (checkTolerances()) { #ifdef DEBUG - VR_INFO << "Tolerances ok, loop:" << step << endl; + VR_INFO << "Tolerances ok, loop:" << step << std::endl; #endif return true; } @@ -51,7 +51,7 @@ bool HierarchicalIKSolver::computeSteps(float stepSize, float minChange, int max if (delta.norm() < minChange) { #ifdef DEBUG - VR_INFO << "Could not improve result any more (dTheta.norm()=" << delta.norm() << "), loop:" << step << endl; + VR_INFO << "Could not improve result any more (dTheta.norm()=" << delta.norm() << "), loop:" << step << std::endl; #endif return false; } diff --git a/VirtualRobot/IK/JacobiProvider.cpp b/VirtualRobot/IK/JacobiProvider.cpp index ec464538d48b322a9ae64a09675f31baf0ca8a9c..86b0c92f818a788f0cf04656b964712e91655540 100644 --- a/VirtualRobot/IK/JacobiProvider.cpp +++ b/VirtualRobot/IK/JacobiProvider.cpp @@ -50,7 +50,7 @@ namespace VirtualRobot clock_t endT = clock(); float diffClock1 = (float)(((float)(startT2 - startT) / (float)CLOCKS_PER_SEC) * 1000.0f); float diffClock2 = (float)(((float)(endT - startT2) / (float)CLOCKS_PER_SEC) * 1000.0f); - cout << "getPseudoInverseJacobianMatrix time1:" << diffClock1 << ", time2: " << diffClock2 << endl; + std::cout << "getPseudoInverseJacobianMatrix time1:" << diffClock1 << ", time2: " << diffClock2 << std::endl; #endif return res; } @@ -69,7 +69,7 @@ namespace VirtualRobot clock_t endT = clock(); float diffClock1 = (float)(((float)(startT2 - startT) / (float)CLOCKS_PER_SEC) * 1000.0f); float diffClock2 = (float)(((float)(endT - startT2) / (float)CLOCKS_PER_SEC) * 1000.0f); - cout << "getPseudoInverseJacobianMatrix time1:" << diffClock1 << ", time2: " << diffClock2 << endl; + std::cout << "getPseudoInverseJacobianMatrix time1:" << diffClock1 << ", time2: " << diffClock2 << std::endl; #endif return res; } @@ -234,7 +234,7 @@ namespace VirtualRobot clock_t endT = clock(); float diffClock = (float)(((float)(endT - startT) / (float)CLOCKS_PER_SEC) * 1000.0f); //if (diffClock>10.0f) - cout << "Inverse Jacobi time:" << diffClock << endl; + std::cout << "Inverse Jacobi time:" << diffClock << std::endl; #endif } @@ -328,7 +328,7 @@ namespace VirtualRobot clock_t endT = clock(); float diffClock = (float)(((float)(endT - startT) / (float)CLOCKS_PER_SEC) * 1000.0f); //if (diffClock>10.0f) - cout << "Inverse Jacobi time:" << diffClock << endl; + std::cout << "Inverse Jacobi time:" << diffClock << std::endl; #endif } @@ -376,9 +376,9 @@ namespace VirtualRobot void JacobiProvider::print() { - cout << "IK solver:" << name << endl; - cout << "==========================" << endl; - cout << "RNS:" << rns->getName() << " with " << rns->getSize() << " joints" << endl; + std::cout << "IK solver:" << name << std::endl; + std::cout << "==========================" << std::endl; + std::cout << "RNS:" << rns->getName() << " with " << rns->getSize() << " joints" << std::endl; } bool JacobiProvider::isInitialized() diff --git a/VirtualRobot/IK/PoseQualityExtendedManipulability.cpp b/VirtualRobot/IK/PoseQualityExtendedManipulability.cpp index 0ecb2e85a3ae5c008cbfe5d3e13564762acb174b..2b3290a558bd5f4396bba136d888bc79d7a631c5 100644 --- a/VirtualRobot/IK/PoseQualityExtendedManipulability.cpp +++ b/VirtualRobot/IK/PoseQualityExtendedManipulability.cpp @@ -51,7 +51,7 @@ namespace VirtualRobot if (!getDetailedAnalysis(jac, rns, currentManipData, considerFirstSV)) { - VR_ERROR << "ERROR" << endl; + VR_ERROR << "ERROR" << std::endl; return 0; } @@ -70,7 +70,7 @@ namespace VirtualRobot break; default: - VR_ERROR << "NYI..." << endl; + VR_ERROR << "NYI..." << std::endl; } return 0; @@ -100,7 +100,7 @@ namespace VirtualRobot if (boost::math::isinf(w) || boost::math::isinf(-w) || boost::math::isnan(w)) { - cout << "nan" << endl; + std::cout << "nan" << std::endl; } @@ -133,9 +133,9 @@ namespace VirtualRobot if (verbose) { - cout << "PEN LO:"; + std::cout << "PEN LO:"; VirtualRobot::MathTools::print(penLo); - cout << "PEN HI:"; + std::cout << "PEN HI:"; VirtualRobot::MathTools::print(penHi); } } @@ -171,10 +171,10 @@ namespace VirtualRobot if (verbose) { - cout << "++++++++++++++++++++++++++++++" << endl; - cout << "+++++++++++++++++++ d:" << d << endl; - cout << "+++++++++++++++++++ p1:" << p1 << endl; - cout << "++++++++++++++++++++++++++++++" << endl; + std::cout << "++++++++++++++++++++++++++++++" << std::endl; + std::cout << "+++++++++++++++++++ d:" << d << std::endl; + std::cout << "+++++++++++++++++++ p1:" << p1 << std::endl; + std::cout << "++++++++++++++++++++++++++++++" << std::endl; } Eigen::VectorXf v2(6); @@ -190,7 +190,7 @@ namespace VirtualRobot if (verbose) { - cout << "PEN OBST (gradient)1:"; + std::cout << "PEN OBST (gradient)1:"; VirtualRobot::MathTools::print(penObst); } @@ -199,7 +199,7 @@ namespace VirtualRobot if (verbose) { - cout << "PEN OBST (gradient)2:"; + std::cout << "PEN OBST (gradient)2:"; VirtualRobot::MathTools::print(penObst); } @@ -207,7 +207,7 @@ namespace VirtualRobot if (verbose) { - cout << "PEN OBST (gradient):"; + std::cout << "PEN OBST (gradient):"; VirtualRobot::MathTools::print(penObst); } @@ -219,7 +219,7 @@ namespace VirtualRobot if (verbose) { - cout << "PEN OBST (pen factor):"; + std::cout << "PEN OBST (pen factor):"; VirtualRobot::MathTools::print(penObst); } @@ -246,14 +246,14 @@ namespace VirtualRobot if (verbose) { - cout << "PEN OBST (penObstLo):\n" << penObstLo << endl; - cout << "PEN OBST (penObstHi):\n" << penObstHi << endl; + std::cout << "PEN OBST (penObstLo):\n" << penObstLo << std::endl; + std::cout << "PEN OBST (penObstHi):\n" << penObstHi << std::endl; } if (verbose) { - cout << "ObstVect: d=" << obstVect.norm() << ", v="; + std::cout << "ObstVect: d=" << obstVect.norm() << ", v="; MathTools::print(obstVect); } } @@ -365,9 +365,9 @@ namespace VirtualRobot if (printInfo) { - cout << "Sing Values:\n" << sv << endl; - cout << "U:\n" << U << endl; - cout << "Sing Vectors (scaled according to SingValues:\n" << singVectors << endl; + std::cout << "Sing Values:\n" << sv << std::endl; + std::cout << "U:\n" << U << std::endl; + std::cout << "Sing Vectors (scaled according to SingValues:\n" << singVectors << std::endl; } return true; @@ -405,8 +405,8 @@ namespace VirtualRobot //bool verbose = false; if (verbose) { - cout << "considerFirstSV=" << considerFirstSV << endl; - cout << "JAC:\n" << endl; + std::cout << "considerFirstSV=" << considerFirstSV << std::endl; + std::cout << "JAC:\n" << std::endl; MathTools::printMat(storeData.jac); } @@ -431,7 +431,7 @@ namespace VirtualRobot if (verbose && i < 4) { - cout << "JAC PEN:" << i << endl; + std::cout << "JAC PEN:" << i << std::endl; MathTools::printMat(storeData.jacPen[i]); } @@ -474,7 +474,7 @@ namespace VirtualRobot result_v = tmpRes; } - //cout << "## k:" << k << " -> tmpRes: " << tmpRes << ", result:" << result << endl; + //cout << "## k:" << k << " -> tmpRes: " << tmpRes << ", result:" << result << std::endl; // cond numb if (sv.rows() >= 2) @@ -520,8 +520,8 @@ namespace VirtualRobot if (verbose) { - cout << "## k:" << k << " -> minSV: " << minSV_loc << ", maxSV:" << maxSV_loc << endl; - cout << "## pen jac:\n" << endl; + std::cout << "## k:" << k << " -> minSV: " << minSV_loc << ", maxSV:" << maxSV_loc << std::endl; + std::cout << "## pen jac:\n" << std::endl; MathTools::printMat(storeData.jacPen[k]); } } @@ -817,8 +817,8 @@ namespace VirtualRobot if (verbose) { - cout << "## -> minSV: " << minSV_loc << ", maxSV:" << maxSV_loc << endl; - cout << "## pen jac:\n" << jacPen << endl; + std::cout << "## -> minSV: " << minSV_loc << ", maxSV:" << maxSV_loc << std::endl; + std::cout << "## pen jac:\n" << jacPen << std::endl; } } } diff --git a/VirtualRobot/IK/PoseQualityManipulability.cpp b/VirtualRobot/IK/PoseQualityManipulability.cpp index 5b9cbbd9c2b6701f89a68c8c34674dbcd1fb97ea..c9b8d0430431ce02c95d1801d799538551af6c42 100644 --- a/VirtualRobot/IK/PoseQualityManipulability.cpp +++ b/VirtualRobot/IK/PoseQualityManipulability.cpp @@ -28,21 +28,21 @@ namespace VirtualRobot { if (verbose) { - cout << "*** PoseQualityManipulability::getSingularVectorCartesian()\n"; + std::cout << "*** PoseQualityManipulability::getSingularVectorCartesian()\n"; } Eigen::MatrixXf jac = jacobian->getJacobianMatrix(rns->getTCP()); - //cout << "JAC\n:" << jac << endl; + //cout << "JAC\n:" << jac << std::endl; // penalize rotation jac.block(3, 0, 3, jac.cols()) *= penalizeRotationFactor; - //cout << "scaled JAC\n:" << jac << endl; + //cout << "scaled JAC\n:" << jac << std::endl; Eigen::JacobiSVD<Eigen::MatrixXf> svd(jac, Eigen::ComputeThinU | Eigen::ComputeThinV); Eigen::MatrixXf U = svd.matrixU(); Eigen::VectorXf sv = svd.singularValues(); if (verbose) { - cout << "U:\n" << U << endl; + std::cout << "U:\n" << U << std::endl; } if (sv.rows() == 0) @@ -52,14 +52,14 @@ namespace VirtualRobot if (verbose) { - cout << "sv:\n" << sv << endl; + std::cout << "sv:\n" << sv << std::endl; } float maxEV = sv(0); if (verbose) { - cout << "maxEV:" << maxEV << endl; + std::cout << "maxEV:" << maxEV << std::endl; } /*for (int i=0;i<sv.rows();i++) @@ -70,7 +70,7 @@ namespace VirtualRobot }*/ if (verbose) { - cout << "result:\n" << U << endl; + std::cout << "result:\n" << U << std::endl; } return U; @@ -168,7 +168,7 @@ namespace VirtualRobot } default: - VR_ERROR << "Manipulability type not implemented..." << endl; + VR_ERROR << "Manipulability type not implemented..." << std::endl; } if (penJointLimits) @@ -225,7 +225,7 @@ namespace VirtualRobot float result = 1.0f - exp(-penJointLimits_k * p); if (verbose) - cout << "Pen factor:" << result << endl; + std::cout << "Pen factor:" << result << std::endl; return result; } diff --git a/VirtualRobot/IK/PoseQualityMeasurement.cpp b/VirtualRobot/IK/PoseQualityMeasurement.cpp index 7112105dbcc5b96518e842dd53c818d04bd406a4..de0dba966a9f66ea83857c47dd7949b4103d286e 100644 --- a/VirtualRobot/IK/PoseQualityMeasurement.cpp +++ b/VirtualRobot/IK/PoseQualityMeasurement.cpp @@ -25,14 +25,14 @@ namespace VirtualRobot float PoseQualityMeasurement::getPoseQuality() { - VR_WARNING << "Please use derived classes..." << endl; + VR_WARNING << "Please use derived classes..." << std::endl; return 0.0f; } float PoseQualityMeasurement::getPoseQuality(const Eigen::VectorXf& /*direction*/) { // VR_ASSERT(direction.rows() == 3 || direction.rows() == 6); - VR_WARNING << "Please use derived classes..." << endl; + VR_WARNING << "Please use derived classes..." << std::endl; return 0.0f; } diff --git a/VirtualRobot/IK/SupportPolygon.cpp b/VirtualRobot/IK/SupportPolygon.cpp index 2b18b793c045e48e30923c371525fbd019eb7409..7a5c29adf0d1023826df4bd54b5dda1778df7417 100644 --- a/VirtualRobot/IK/SupportPolygon.cpp +++ b/VirtualRobot/IK/SupportPolygon.cpp @@ -108,7 +108,7 @@ namespace VirtualRobot if (!MathTools::isInside(com2D, ch)) { - //cout << "CoM outside of support polygon" << endl; + //cout << "CoM outside of support polygon" << std::endl; return 0.0f; } @@ -146,10 +146,10 @@ namespace VirtualRobot //(ptOnLine-com2D).squaredNorm(); if (d < minDistCoM) { - /*cout << "minDistCom:" << sqrtf(d) << ", com2D:" << com2D(0) << "," << com2D(1) << endl; - cout << "minDistCom:" << sqrtf(d) << ", pt1:" << pt1(0) << "," << pt1(1) << endl; - cout << "minDistCom:" << sqrtf(d) << ", pt2:" << pt2(0) << "," << pt2(1) << endl; - cout << "minDistCom:" << sqrtf(d) << ", ptOnLine:" << ptOnLine(0) << "," << ptOnLine(1) << endl;*/ + /*cout << "minDistCom:" << sqrtf(d) << ", com2D:" << com2D(0) << "," << com2D(1) << std::endl; + std::cout << "minDistCom:" << sqrtf(d) << ", pt1:" << pt1(0) << "," << pt1(1) << std::endl; + std::cout << "minDistCom:" << sqrtf(d) << ", pt2:" << pt2(0) << "," << pt2(1) << std::endl; + std::cout << "minDistCom:" << sqrtf(d) << ", ptOnLine:" << ptOnLine(0) << "," << ptOnLine(1) << std::endl;*/ minDistCoM = d; } } @@ -157,8 +157,8 @@ namespace VirtualRobot minDistCenter = sqrtf(minDistCenter); minDistCoM = sqrtf(minDistCoM); - //cout << "Dist center -> border:" << minDistCenter << endl; - //cout << "Dist com -> border:" << minDistCoM << endl; + //cout << "Dist center -> border:" << minDistCenter << std::endl; + //cout << "Dist com -> border:" << minDistCoM << std::endl; float res = 0.0f; if (fabs(minDistCenter) > 1e-8) @@ -166,7 +166,7 @@ namespace VirtualRobot res = minDistCoM / minDistCenter; } - //cout << "Stability Value:" << res << endl; + //cout << "Stability Value:" << res << std::endl; if (res > 1.0f) { res = 1.0f; diff --git a/VirtualRobot/IK/constraints/BalanceConstraint.cpp b/VirtualRobot/IK/constraints/BalanceConstraint.cpp index ab399f1a275beccef6650986280b9a132cfa78a9..6de29ce36d73ee3224ca37b37b501c3eb727eb28 100644 --- a/VirtualRobot/IK/constraints/BalanceConstraint.cpp +++ b/VirtualRobot/IK/constraints/BalanceConstraint.cpp @@ -165,7 +165,7 @@ void BalanceConstraint::initialize(const RobotPtr& robot, const RobotNodeSetPtr& supportPolygon.reset(new SupportPolygon(contactNodes)); differnentiableStability.reset(new BalanceConstraintOptimizationFunction(supportPolygon)); - VR_INFO << "COM height:" << height << endl; + VR_INFO << "COM height:" << height << std::endl; int dim = 2; if (considerCoMHeight) @@ -205,7 +205,7 @@ void BalanceConstraint::updateSupportPolygon() goal.head(2) = supportPolygonCenter; goal(2) = height; comIK->setGoal(goal, tolerance); - //VR_INFO << "CoM Height of Inversed Robot set to:" << goal(2) << endl; + //VR_INFO << "CoM Height of Inversed Robot set to:" << goal(2) << std::endl; } else { diff --git a/VirtualRobot/Import/COLLADA-light/ColladaSimox.cpp b/VirtualRobot/Import/COLLADA-light/ColladaSimox.cpp index 8de37d9b62de1ae6d1f023bbbab45c8c9be7976a..5aeaa919e0b2d815cf5c2f86c541f020435eea76 100644 --- a/VirtualRobot/Import/COLLADA-light/ColladaSimox.cpp +++ b/VirtualRobot/Import/COLLADA-light/ColladaSimox.cpp @@ -162,23 +162,23 @@ namespace Collada if (DBG_NODE("RRKnee_Joint")) { - cout << "Node: " << this->name; - cout << jointLimitLow << "," << jointLimitHigh << "," << acceleration << "," << deceleration << "," << velocity << "," << torque << endl; - cout << this->joint_axis.name() << endl; + std::cout << "Node: " << this->name; + std::cout << jointLimitLow << "," << jointLimitHigh << "," << acceleration << "," << deceleration << "," << velocity << "," << torque << std::endl; + std::cout << this->joint_axis.name() << std::endl; preJointTransformation = Eigen::Matrix4f::Identity(); for (pugi::xml_node node : this->preJoint) { - cout << getTransform(node) << endl; + std::cout << getTransform(node) << std::endl; preJointTransformation = preJointTransformation * getTransform(node, scaleFactor); } - cout << preJointTransformation << endl; + std::cout << preJointTransformation << std::endl; } /* Compute bounding box for debug reasons */ //this->visualizeBoundingBox(); VirtualRobot::VisualizationNodePtr visualizationNode(new VirtualRobot::CoinVisualizationNode(this->visualization)); - //cout << "node " << this->name << "#Faces" << visualizationNode->getNumFaces() << endl; + //cout << "node " << this->name << "#Faces" << visualizationNode->getNumFaces() << std::endl; VirtualRobot::CollisionModelPtr collisionModel; //(new VirtualRobot::CollisionModel(visualizationNode)); // Check for rigid body dynamics and collision models. @@ -200,7 +200,7 @@ namespace Collada VirtualRobot::VisualizationNodePtr collisionNode(new VirtualRobot::CoinVisualizationNode(this->collisionModel)); collisionModel.reset(new VirtualRobot::CollisionModel(collisionNode)); - // cout << "Physics : " << name << endl << massFrameTransformation << endl << scaleFactor << massFrameTransformation.block<3,3>(0,0)*inertia << endl << mass << endl << com << endl; + // std::cout << "Physics : " << name << endl << massFrameTransformation << endl << scaleFactor << massFrameTransformation.block<3,3>(0,0)*inertia << endl << mass << endl << com << std::endl; physics.comLocation = VirtualRobot::SceneObject::Physics::eCustom; physics.localCoM = com; @@ -209,7 +209,7 @@ namespace Collada if (this->name.compare("RRKnee_joint") == 0) { - cout << "Physics RRKnee_Joint: " << massFrameTransformation << endl << scaleFactor << massFrameTransformation.block<3, 3>(0, 0)*inertia << endl << mass << endl << com << endl; + std::cout << "Physics RRKnee_Joint: " << massFrameTransformation << endl << scaleFactor << massFrameTransformation.block<3, 3>(0, 0)*inertia << endl << mass << endl << com << std::endl; } } @@ -232,7 +232,7 @@ namespace Collada if (!this->simoxRobotNode) { - cout << "Node " << this->name << " not Created" << endl; + std::cout << "Node " << this->name << " not Created" << std::endl; } #ifdef COLLADA_IMPORT_USE_SENSORS diff --git a/VirtualRobot/Import/COLLADA-light/collada.cpp b/VirtualRobot/Import/COLLADA-light/collada.cpp index 18e70fe78d7909b316b52691842544f27172cd60..d4b857111d2635906d98d6388bde6038f75d8a8d 100644 --- a/VirtualRobot/Import/COLLADA-light/collada.cpp +++ b/VirtualRobot/Import/COLLADA-light/collada.cpp @@ -188,7 +188,7 @@ namespace Collada robotNode->parent = parents.back(); } - //BOOST_FOREACH(pugi::xml_node n, stack[depth()]) cout << "Ignored: " << n.name() << endl; + //BOOST_FOREACH(pugi::xml_node n, stack[depth()]) std::cout << "Ignored: " << n.name() << std::endl; parents.push_back(robotNode); } @@ -236,12 +236,12 @@ namespace Collada if (!result) { - cout << "Could not load:" << result.description() << endl; + std::cout << "Could not load:" << result.description() << std::endl; } std::cout << "Version: " << doc.child("COLLADA").attribute("version").as_float() << std::endl; - std::cout << "Scene: " << doc.child("COLLADA").child("scene").child("instance_kinematics_scene").attribute("url").as_string() << endl; + std::cout << "Scene: " << doc.child("COLLADA").child("scene").child("instance_kinematics_scene").attribute("url").as_string() << std::endl; pugi::xml_node collada = doc.child("COLLADA"); pugi::xml_node scene = collada.child("scene"); @@ -249,7 +249,7 @@ namespace Collada // There is probably ean error here ... the // before scene should not be required - // cout << "url:" << collada.select_nodes("scene/instance_kinematics_scene/@url").begin()->node().value() << "KS: " << kinematics_scene.name() << endl; + // std::cout << "url:" << collada.select_nodes("scene/instance_kinematics_scene/@url").begin()->node().value() << "KS: " << kinematics_scene.name() << std::endl; pugi::xml_node kinematics_scene = scene.select_single_node("//library_kinematics_scenes/kinematics_scene[@id=substring(//scene/instance_kinematics_scene/@url,2)]").node(); @@ -339,18 +339,18 @@ namespace Collada } robotNode->name = robotNode->joint_axis.parent().attribute("name").value(); - //cout << "Name: " << robotNode->name << endl; + //cout << "Name: " << robotNode->name << std::endl; robotNode->motion_info = jointMap[robotNode->joint_axis].first; robotNode->kinematics_info = jointMap[robotNode->joint_axis].second; - //cout << robotNode->kinematics_info.child("limits").child("min").child_value("float") << endl; + //cout << robotNode->kinematics_info.child("limits").child("min").child_value("float") << std::endl; robotNodeSet.push_back(robotNode); std::string visualizationTarget = bind.node().attribute("target").value(); visualizationMap[resolveSIDREF(collada, visualizationTarget, IN_VISUAL_SCENES)] = robotNode; - //cout << "Vizualization: " << visualizationTarget << "," << resolveSIDREF(collada,visualizationTarget,IN_VISUAL_SCENES).name() << endl; - //cout << robotNode->joint_axis.parent().name() << endl; + //cout << "Vizualization: " << visualizationTarget << "," << resolveSIDREF(collada,visualizationTarget,IN_VISUAL_SCENES).name() << std::endl; + //cout << robotNode->joint_axis.parent().name() << std::endl; structureMap[robotNode->joint_axis.parent()] = robotNode; } { @@ -370,7 +370,7 @@ namespace Collada // Now optain the kinematic structure BOOST_FOREACH(pugi::xml_node model, kinematicsModels) { - cout << model.name() << endl; + std::cout << model.name() << std::endl; ModelWalker modelWalker(structureMap); #ifdef COLLADA_IMPORT_USE_SENSORS modelWalker.setSensorMap(sensorMap); diff --git a/VirtualRobot/Import/COLLADA-light/inventor.cpp b/VirtualRobot/Import/COLLADA-light/inventor.cpp index 8619d9ccbd34d8e64a2e518014cd6e7964637510..f44eb036faa406e76912a0c4b0f026bb1386c33f 100644 --- a/VirtualRobot/Import/COLLADA-light/inventor.cpp +++ b/VirtualRobot/Import/COLLADA-light/inventor.cpp @@ -122,7 +122,7 @@ namespace Collada { if (this->parent) { - cout << "Parent of " << this->name << " is " << this->parent->name << endl; + std::cout << "Parent of " << this->name << " is " << this->parent->name << std::endl; std::dynamic_pointer_cast<InventorRobotNode>(this->parent)->visualization->addChild(this->visualization); } else @@ -209,7 +209,7 @@ namespace Collada #ifdef TIMER_DEBUG boost::timer::auto_cpu_timer timer(1, string("Inventor (") + string(geometry.attribute("id").value()) + string("): %t sec CPU, %w sec real\n")); - cout << "Faces: " ; + std::cout << "Faces: " ; #endif // Temporarily skip complicated models @@ -217,7 +217,7 @@ namespace Collada if (nPolylist > 5) { - cout << "More than five (" << nPolylist << ") seperated meshes .. skipping (" << geometry.attribute("id").value() << ")\n"; + std::cout << "More than five (" << nPolylist << ") seperated meshes .. skipping (" << geometry.attribute("id").value() << ")\n"; // return; } @@ -251,7 +251,7 @@ namespace Collada std::vector<int> p = getVector<int>(polylist.node().child_value("p")); std::vector<int> vcount = getVector<int>(polylist.node().child_value("vcount")); #ifdef TIMER_DEBUG - cout << vcount.size() << ", " << flush; + std::cout << vcount.size() << ", " << flush; #endif pugi::xml_node vertexInputNode = polylist.node().select_single_node(".//input[@semantic='VERTEX']").node(); @@ -290,7 +290,7 @@ namespace Collada } #ifdef TIMER_DEBUG - cout << endl; + std::cout << std::endl; #endif } diff --git a/VirtualRobot/Import/SimoxXMLFactory.cpp b/VirtualRobot/Import/SimoxXMLFactory.cpp index b0f409bf83246124f3898550afd5d5c4c40c66f3..17d2f26456ab24c015c5752899f1e18cf2c0e6e3 100644 --- a/VirtualRobot/Import/SimoxXMLFactory.cpp +++ b/VirtualRobot/Import/SimoxXMLFactory.cpp @@ -27,14 +27,14 @@ namespace VirtualRobot } catch (VirtualRobotException& e) { - VR_ERROR << " ERROR while loading robot from file:" << filename << endl; + VR_ERROR << " ERROR while loading robot from file:" << filename << std::endl; VR_ERROR << e.what(); return robot; } if (!robot) { - VR_ERROR << " ERROR while loading robot from file:" << filename << endl; + VR_ERROR << " ERROR while loading robot from file:" << filename << std::endl; } return robot; diff --git a/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp b/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp index dd30a8293fd3ce7fdb843906832798606ec0c2e7..9aad451a0b7b8062726fb0646658ae2814f98e61 100644 --- a/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp +++ b/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp @@ -43,7 +43,7 @@ namespace VirtualRobot if (!urdf_model) { - VR_ERROR << "Error opening urdf file " << filename << endl; + VR_ERROR << "Error opening urdf file " << filename << std::endl; } else { @@ -178,7 +178,7 @@ namespace VirtualRobot result = f; if (!VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(result)) { - VR_ERROR << "Could not determine absolute path of " << result << endl; + VR_ERROR << "Could not determine absolute path of " << result << std::endl; } } } @@ -248,7 +248,7 @@ namespace VirtualRobot break; default: - VR_WARNING << "urdf::Geometry type nyi..." << endl; + VR_WARNING << "urdf::Geometry type nyi..." << std::endl; } if (res) diff --git a/VirtualRobot/ManipulationObject.cpp b/VirtualRobot/ManipulationObject.cpp index aae4771262d0b99125277cada2a0fd462927c272..30def0c0d466b45fabedd0385a8965bcf032f2d6 100644 --- a/VirtualRobot/ManipulationObject.cpp +++ b/VirtualRobot/ManipulationObject.cpp @@ -28,20 +28,20 @@ namespace VirtualRobot { if (printDecoration) { - cout << "**** Manipulation Object ****" << endl; + std::cout << "**** Manipulation Object ****" << std::endl; } Obstacle::print(false); for (size_t i = 0; i < graspSets.size(); i++) { - cout << "* Grasp set " << i << ":" << endl; + std::cout << "* Grasp set " << i << ":" << std::endl; graspSets[i]->print(); } if (printDecoration) { - cout << endl; + std::cout << std::endl; } } @@ -214,7 +214,7 @@ namespace VirtualRobot if (!result) { - VR_ERROR << "Cloning failed.." << endl; + VR_ERROR << "Cloning failed.." << std::endl; return result; } @@ -246,7 +246,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_ERROR << "Could not create factory for visu type " << visualizationType << endl; + VR_ERROR << "Could not create factory for visu type " << visualizationType << std::endl; return result; } @@ -256,7 +256,7 @@ namespace VirtualRobot if (!visu) { - VR_ERROR << "Could not create sphere visualization with visu type " << visualizationType << endl; + VR_ERROR << "Could not create sphere visualization with visu type " << visualizationType << std::endl; return result; } diff --git a/VirtualRobot/MathTools.cpp b/VirtualRobot/MathTools.cpp index 2a09eb60ae17c988ed5e0d99721180e2a8f3c23b..00f17f832432b1bebc4f918fe090fa8f1f59c4d3 100644 --- a/VirtualRobot/MathTools.cpp +++ b/VirtualRobot/MathTools.cpp @@ -884,17 +884,17 @@ namespace VirtualRobot for (size_t i = 0; i < v.size(); i++) { - cout << v[i]; + std::cout << v[i]; if (i != v.size() - 1) { - cout << ","; + std::cout << ","; } } if (endline) { - cout << endl; + std::cout << std::endl; } std::cout << std::resetiosflags(std::ios::fixed); @@ -908,17 +908,17 @@ namespace VirtualRobot for (int i = 0; i < v.rows(); i++) { - cout << v(i); + std::cout << v(i); if (i != v.rows() - 1) { - cout << ","; + std::cout << ","; } } if (endline) { - cout << endl; + std::cout << std::endl; } std::cout << std::resetiosflags(std::ios::fixed); @@ -934,20 +934,20 @@ namespace VirtualRobot { for (int j = 0; j < m.cols(); j++) { - cout << m(i, j); + std::cout << m(i, j); if (j != m.cols() - 1) { - cout << ","; + std::cout << ","; } } - cout << endl; + std::cout << std::endl; } if (endline) { - cout << endl; + std::cout << std::endl; } std::cout << std::resetiosflags(std::ios::fixed); @@ -1074,11 +1074,11 @@ namespace VirtualRobot if (!randomLinearlyIndependentVector(tmpBasisV, newBasisVector)) { - VR_ERROR << "Could not find linearly independent basis vector?! " << endl; + VR_ERROR << "Could not find linearly independent basis vector?! " << std::endl; for (size_t i = 0; i < dim; i++) { - cout << "vec " << i << ":\n" << basis[i] << endl; + std::cout << "vec " << i << ":\n" << basis[i] << std::endl; } return false; @@ -1127,10 +1127,10 @@ namespace VirtualRobot Eigen::VectorXf newBasisVector; if (!randomLinearlyIndependentVector(tmpBasis,newBasisVector)) { - VR_ERROR << "Could not find linearly independent basis vector?! " << endl; + VR_ERROR << "Could not find linearly independent basis vector?! " << std::endl; for (int i=0;i<dim;i++) { - cout << "vec " << i << ":\n" << basis[i] << endl; + std::cout << "vec " << i << ":\n" << basis[i] << std::endl; } return false; } @@ -1234,7 +1234,7 @@ namespace VirtualRobot if (loop > 100) { - VR_ERROR << "Could not determine independent vector, aborting after 100 tries" << endl; + VR_ERROR << "Could not determine independent vector, aborting after 100 tries" << std::endl; return false; } } @@ -1897,7 +1897,7 @@ namespace VirtualRobot if (!ch || ch->vertices.size() == 0) { - VR_WARNING << "Null data..." << endl; + VR_WARNING << "Null data..." << std::endl; return c; } @@ -1944,7 +1944,7 @@ namespace VirtualRobot double a0 = 2*acos((double)q.w / s1); double b0 = 2*acos((double)q.x / s2); if (std::abs(a0-b0) > 1e-8) - std::cout << "0: " << a0 << "!=" << b0 << endl; + std::cout << "0: " << a0 << "!=" << b0 << std::endl; res(0) = a0; s1 = sin((double)res(0) * 0.5); @@ -1953,13 +1953,13 @@ namespace VirtualRobot if (std::abs(a-b) > 1e-8) { - std::cout << "1: " << a << "!=" << b << endl; + std::cout << "1: " << a << "!=" << b << std::endl; Eigen::Vector3f test1; test1 << (float)res(0) , float(a) , float(res(2)); Quaternion q1 = hopf2quat(test1); if (std::abs(q1.w-q.w)<1e-6 && std::abs(q1.x-q.x)<1e-6 && std::abs(q1.y-q.y)<1e-6 && std::abs(q1.z-q.z)<1e-6) { - cout << "TEST 1 ok" << endl; + std::cout << "TEST 1 ok" << std::endl; res(1) = a; } else { @@ -1967,10 +1967,10 @@ namespace VirtualRobot Quaternion q2 = hopf2quat(test1); if (std::abs(q2.w-q.w)<1e-6 && std::abs(q2.x-q.x)<1e-6 && std::abs(q2.y-q.y)<1e-6 && std::abs(q2.z-q.z)<1e-6) { - cout << "TEST 2 ok" << endl; + std::cout << "TEST 2 ok" << std::endl; res(1) = b; } - cout << "TEST 1-4 failed!!!" << endl; + std::cout << "TEST 1-4 failed!!!" << std::endl; res(1) = a; diff --git a/VirtualRobot/Nodes/ForceTorqueSensor.cpp b/VirtualRobot/Nodes/ForceTorqueSensor.cpp index 959a68bd5dac42a5851a93cc4a97aee20b6ddf0e..5fb80c5a1e3187b6d04b425654167c0c30e8961c 100644 --- a/VirtualRobot/Nodes/ForceTorqueSensor.cpp +++ b/VirtualRobot/Nodes/ForceTorqueSensor.cpp @@ -54,7 +54,7 @@ namespace VirtualRobot { if (printDecoration) { - cout << "******** ForceTorqueSensor ********" << endl; + std::cout << "******** ForceTorqueSensor ********" << std::endl; } Sensor::print(printChildren, false); @@ -83,14 +83,14 @@ namespace VirtualRobot pre += t; } - ss << pre << "<Sensor type='" << ForceTorqueSensorFactory::getName() << "' name='" << name << "'>" << endl; + ss << pre << "<Sensor type='" << ForceTorqueSensorFactory::getName() << "' name='" << name << "'>" << std::endl; std::string pre2 = pre + t; - ss << pre << "<Transform>" << endl; + ss << pre << "<Transform>" << std::endl; ss << BaseIO::toXML(rnTransformation, pre2); - ss << pre << "</Transform>" << endl; + ss << pre << "</Transform>" << std::endl; - ss << pre << "</Sensor>" << endl; + ss << pre << "</Sensor>" << std::endl; return ss.str(); } diff --git a/VirtualRobot/Nodes/RobotNode.cpp b/VirtualRobot/Nodes/RobotNode.cpp index 9c9631c73cd45ad84b7fbd9745f154a9bc16e0f8..6eb876494f7cda17b34dcd3079b28967f98ea976 100644 --- a/VirtualRobot/Nodes/RobotNode.cpp +++ b/VirtualRobot/Nodes/RobotNode.cpp @@ -123,7 +123,7 @@ namespace VirtualRobot break; default: - VR_ERROR << "RobotNodeType nyi..." << endl; + VR_ERROR << "RobotNodeType nyi..." << std::endl; } @@ -404,7 +404,7 @@ namespace VirtualRobot if (!res && verbose) { - VR_INFO << "Joint: " << getName() << ": joint value (" << jointValue << ") is out of joint boundaries (lo:" << jointLimitLo << ", hi: " << jointLimitHi << ")" << endl; + VR_INFO << "Joint: " << getName() << ": joint value (" << jointValue << ") is out of joint boundaries (lo:" << jointLimitLo << ", hi: " << jointLimitHi << ")" << std::endl; } return res; @@ -420,56 +420,56 @@ namespace VirtualRobot if (printDecoration) { - cout << "******** RobotNode ********" << endl; + std::cout << "******** RobotNode ********" << std::endl; } - cout << "* Name: " << name << endl; - cout << "* Parent: "; + std::cout << "* Name: " << name << std::endl; + std::cout << "* Parent: "; SceneObjectPtr p = this->getParent(); if (p) { - cout << p->getName() << endl; + std::cout << p->getName() << std::endl; } else { - cout << " -- " << endl; + std::cout << " -- " << std::endl; } - cout << "* Children: "; + std::cout << "* Children: "; if (this->getChildren().size() == 0) { - cout << " -- " << endl; + std::cout << " -- " << std::endl; } for (unsigned int i = 0; i < this->getChildren().size(); i++) { - cout << this->getChildren()[i]->getName() << ", "; + std::cout << this->getChildren()[i]->getName() << ", "; } - cout << endl; + std::cout << std::endl; physics.print(); - cout << "* Limits: Lo: " << jointLimitLo << ", Hi: " << jointLimitHi << endl; - cout << "* Limitless: " << (limitless ? "true" : "false") << endl; + std::cout << "* Limits: Lo: " << jointLimitLo << ", Hi: " << jointLimitHi << std::endl; + std::cout << "* Limitless: " << (limitless ? "true" : "false") << std::endl; std::cout << "* max velocity " << maxVelocity << " [m/s]" << std::endl; std::cout << "* max acceleration " << maxAcceleration << " [m/s^2]" << std::endl; std::cout << "* max torque " << maxTorque << " [Nm]" << std::endl; - cout << "* jointValue: " << this->getJointValue() << ", jointValueOffset: " << jointValueOffset << endl; + std::cout << "* jointValue: " << this->getJointValue() << ", jointValueOffset: " << jointValueOffset << std::endl; if (optionalDHParameter.isSet) { - cout << "* DH parameters: "; - cout << " a:" << optionalDHParameter.aMM() << ", d:" << optionalDHParameter.dMM() << ", alpha:" << optionalDHParameter.alphaRadian() << ", theta:" << optionalDHParameter.thetaRadian() << endl; + std::cout << "* DH parameters: "; + std::cout << " a:" << optionalDHParameter.aMM() << ", d:" << optionalDHParameter.dMM() << ", alpha:" << optionalDHParameter.alphaRadian() << ", theta:" << optionalDHParameter.thetaRadian() << std::endl; } else { - cout << "* DH parameters: not specified." << endl; + std::cout << "* DH parameters: not specified." << std::endl; } - cout << "* visualization model: " << endl; + std::cout << "* visualization model: " << std::endl; if (visualizationModel) { @@ -477,10 +477,10 @@ namespace VirtualRobot } else { - cout << " No visualization model" << endl; + std::cout << " No visualization model" << std::endl; } - cout << "* collision model: " << endl; + std::cout << "* collision model: " << std::endl; if (collisionModel) { @@ -488,30 +488,30 @@ namespace VirtualRobot } else { - cout << " No collision model" << endl; + std::cout << " No collision model" << std::endl; } if (initialized) { - cout << "* initialized: true" << endl; + std::cout << "* initialized: true" << std::endl; } else { - cout << "* initialized: false" << endl; + std::cout << "* initialized: false" << std::endl; } { // scope1 std::ostringstream sos; sos << std::setiosflags(std::ios::fixed); - sos << "* localTransformation:" << endl << localTransformation << endl; - sos << "* globalPose:" << endl << getGlobalPose() << endl; - cout << sos.str(); + sos << "* localTransformation:" << endl << localTransformation << std::endl; + sos << "* globalPose:" << endl << getGlobalPose() << std::endl; + std::cout << sos.str(); } // scope1 if (printDecoration) { - cout << "******** End RobotNode ********" << endl; + std::cout << "******** End RobotNode ********" << std::endl; } if (printChildren) @@ -555,7 +555,7 @@ namespace VirtualRobot if (!result) { - VR_ERROR << "Cloning failed.." << endl; + VR_ERROR << "Cloning failed.." << std::endl; return result; } @@ -724,7 +724,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_WARNING << "No visualization factory for name " << visualizationType << endl; + VR_WARNING << "No visualization factory for name " << visualizationType << std::endl; return; } @@ -793,7 +793,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_WARNING << "No visualization factory for name " << visualizationType << endl; + VR_WARNING << "No visualization factory for name " << visualizationType << std::endl; return; } @@ -918,7 +918,7 @@ namespace VirtualRobot } else { - VR_WARNING << "INTERNAL ERROR: getParent==robot but getRoot!=this ?! " << endl; + VR_WARNING << "INTERNAL ERROR: getParent==robot but getRoot!=this ?! " << std::endl; } } @@ -1042,13 +1042,13 @@ namespace VirtualRobot std::string RobotNode::toXML(const std::string& basePath, const std::string& modelPathRelative /*= "models"*/, bool storeSensors) { std::stringstream ss; - ss << "\t<RobotNode name='" << name << "'>" << endl; + ss << "\t<RobotNode name='" << name << "'>" << std::endl; if (!localTransformation.isIdentity()) { - ss << "\t\t<Transform>" << endl; + ss << "\t\t<Transform>" << std::endl; ss << BaseIO::toXML(localTransformation, "\t\t\t"); - ss << "\t\t</Transform>" << endl; + ss << "\t\t</Transform>" << std::endl; } ss << _toXML(modelPathRelative); @@ -1099,11 +1099,11 @@ namespace VirtualRobot if (crn) { - ss << "\t\t<Child name='" << children[i]->getName() << "'/>" << endl; + ss << "\t\t<Child name='" << children[i]->getName() << "'/>" << std::endl; } } - ss << "\t</RobotNode>" << endl << endl; + ss << "\t</RobotNode>" << endl << std::endl; return ss.str(); } diff --git a/VirtualRobot/Nodes/RobotNodePrismatic.cpp b/VirtualRobot/Nodes/RobotNodePrismatic.cpp index c1cd484ec2a27316076aa7c69f940cc44b6f4498..de11d053363c9e60f9bd68f5da836954433bdc50 100644 --- a/VirtualRobot/Nodes/RobotNodePrismatic.cpp +++ b/VirtualRobot/Nodes/RobotNodePrismatic.cpp @@ -145,8 +145,8 @@ namespace VirtualRobot RobotNode::print(false, false); - cout << "* jointTranslationDirection: " << jointTranslationDirection[0] << ", " << jointTranslationDirection[1] << "," << jointTranslationDirection[2] << endl; - cout << "* VisuScaling: "; + std::cout << "* jointTranslationDirection: " << jointTranslationDirection[0] << ", " << jointTranslationDirection[1] << "," << jointTranslationDirection[2] << std::endl; + std::cout << "* VisuScaling: "; if (visuScaling) { @@ -267,22 +267,22 @@ namespace VirtualRobot std::string RobotNodePrismatic::_toXML(const std::string& /*modelPath*/) { std::stringstream ss; - ss << "\t\t<Joint type='prismatic'>" << endl; - ss << "\t\t\t<translationdirection x='" << jointTranslationDirection[0] << "' y='" << jointTranslationDirection[1] << "' z='" << jointTranslationDirection[2] << "'/>" << endl; - ss << "\t\t\t<limits lo='" << jointLimitLo << "' hi='" << jointLimitHi << "' units='mm'/>" << endl; - ss << "\t\t\t<MaxAcceleration value='" << maxAcceleration << "'/>" << endl; - ss << "\t\t\t<MaxVelocity value='" << maxVelocity << "'/>" << endl; - ss << "\t\t\t<MaxTorque value='" << maxTorque << "'/>" << endl; + ss << "\t\t<Joint type='prismatic'>" << std::endl; + ss << "\t\t\t<translationdirection x='" << jointTranslationDirection[0] << "' y='" << jointTranslationDirection[1] << "' z='" << jointTranslationDirection[2] << "'/>" << std::endl; + ss << "\t\t\t<limits lo='" << jointLimitLo << "' hi='" << jointLimitHi << "' units='mm'/>" << std::endl; + ss << "\t\t\t<MaxAcceleration value='" << maxAcceleration << "'/>" << std::endl; + ss << "\t\t\t<MaxVelocity value='" << maxVelocity << "'/>" << std::endl; + ss << "\t\t\t<MaxTorque value='" << maxTorque << "'/>" << std::endl; std::map< std::string, float >::iterator propIt = propagatedJointValues.begin(); while (propIt != propagatedJointValues.end()) { - ss << "\t\t\t<PropagateJointValue name='" << propIt->first << "' factor='" << propIt->second << "'/>" << endl; + ss << "\t\t\t<PropagateJointValue name='" << propIt->first << "' factor='" << propIt->second << "'/>" << std::endl; propIt++; } - ss << "\t\t</Joint>" << endl; + ss << "\t\t</Joint>" << std::endl; return ss.str(); } diff --git a/VirtualRobot/Nodes/RobotNodeRevolute.cpp b/VirtualRobot/Nodes/RobotNodeRevolute.cpp index dc8267915956d492e4a41878af5af6a1f82d54a1..519750ddcc9b896bb6f678fbc600cd8409faa75b 100644 --- a/VirtualRobot/Nodes/RobotNodeRevolute.cpp +++ b/VirtualRobot/Nodes/RobotNodeRevolute.cpp @@ -102,16 +102,16 @@ namespace VirtualRobot if (printDecoration) { - cout << "******** RobotNodeRevolute ********" << endl; + std::cout << "******** RobotNodeRevolute ********" << std::endl; } RobotNode::print(false, false); - cout << "* JointRotationAxis: " << jointRotationAxis[0] << ", " << jointRotationAxis[1] << ", " << jointRotationAxis[2] << endl; + std::cout << "* JointRotationAxis: " << jointRotationAxis[0] << ", " << jointRotationAxis[1] << ", " << jointRotationAxis[2] << std::endl; if (printDecoration) { - cout << "******** End RobotNodeRevolute ********" << endl; + std::cout << "******** End RobotNodeRevolute ********" << std::endl; } std::vector< SceneObjectPtr > children = this->getChildren(); @@ -218,21 +218,21 @@ namespace VirtualRobot std::string RobotNodeRevolute::_toXML(const std::string& /*modelPath*/) { std::stringstream ss; - ss << "\t\t<Joint type='revolute'>" << endl; - ss << "\t\t\t<axis x='" << jointRotationAxis[0] << "' y='" << jointRotationAxis[1] << "' z='" << jointRotationAxis[2] << "'/>" << endl; - ss << "\t\t\t<limits lo='" << jointLimitLo << "' hi='" << jointLimitHi << "' units='radian'/>" << endl; - ss << "\t\t\t<MaxAcceleration value='" << maxAcceleration << "'/>" << endl; - ss << "\t\t\t<MaxVelocity value='" << maxVelocity << "'/>" << endl; - ss << "\t\t\t<MaxTorque value='" << maxTorque << "'/>" << endl; + ss << "\t\t<Joint type='revolute'>" << std::endl; + ss << "\t\t\t<axis x='" << jointRotationAxis[0] << "' y='" << jointRotationAxis[1] << "' z='" << jointRotationAxis[2] << "'/>" << std::endl; + ss << "\t\t\t<limits lo='" << jointLimitLo << "' hi='" << jointLimitHi << "' units='radian'/>" << std::endl; + ss << "\t\t\t<MaxAcceleration value='" << maxAcceleration << "'/>" << std::endl; + ss << "\t\t\t<MaxVelocity value='" << maxVelocity << "'/>" << std::endl; + ss << "\t\t\t<MaxTorque value='" << maxTorque << "'/>" << std::endl; std::map< std::string, float >::iterator propIt = propagatedJointValues.begin(); while (propIt != propagatedJointValues.end()) { - ss << "\t\t\t<PropagateJointValue name='" << propIt->first << "' factor='" << propIt->second << "'/>" << endl; + ss << "\t\t\t<PropagateJointValue name='" << propIt->first << "' factor='" << propIt->second << "'/>" << std::endl; propIt++; } - ss << "\t\t</Joint>" << endl; + ss << "\t\t</Joint>" << std::endl; return ss.str(); } @@ -246,11 +246,11 @@ namespace VirtualRobot while (propIt != propagatedJointValues.end()) { - ss << "\t\t\t<PropagateJointValue name='" << propIt->first << "' factor='" << propIt->second << "'/>" << endl; + ss << "\t\t\t<PropagateJointValue name='" << propIt->first << "' factor='" << propIt->second << "'/>" << std::endl; propIt++; } - ss << "\t\t</Joint>" << endl; + ss << "\t\t</Joint>" << std::endl; return ss.str(); } diff --git a/VirtualRobot/Nodes/Sensor.cpp b/VirtualRobot/Nodes/Sensor.cpp index 249f93ac46c839028a5aa38c260b6f3c24fb31e0..74464323125c7f4c3ca622ec3ffd729fc6ab0d3c 100644 --- a/VirtualRobot/Nodes/Sensor.cpp +++ b/VirtualRobot/Nodes/Sensor.cpp @@ -60,23 +60,23 @@ namespace VirtualRobot { if (printDecoration) { - cout << "******** Sensor ********" << endl; + std::cout << "******** Sensor ********" << std::endl; } - cout << "* Name: " << name << endl; - cout << "* Parent: "; + std::cout << "* Name: " << name << std::endl; + std::cout << "* Parent: "; SceneObjectPtr p = this->getParent(); if (p) { - cout << p->getName() << endl; + std::cout << p->getName() << std::endl; } else { - cout << " -- " << endl; + std::cout << " -- " << std::endl; } - cout << "* visualization model: " << endl; + std::cout << "* visualization model: " << std::endl; if (visualizationModel) { @@ -84,30 +84,30 @@ namespace VirtualRobot } else { - cout << " No visualization model" << endl; + std::cout << " No visualization model" << std::endl; } if (initialized) { - cout << "* initialized: true" << endl; + std::cout << "* initialized: true" << std::endl; } else { - cout << "* initialized: false" << endl; + std::cout << "* initialized: false" << std::endl; } { // scope1 std::ostringstream sos; sos << std::setiosflags(std::ios::fixed); - sos << "* RobotNode to sensor transformation:" << endl << rnTransformation << endl; - sos << "* globalPose:" << endl << getGlobalPose() << endl; - cout << sos.str(); + sos << "* RobotNode to sensor transformation:" << endl << rnTransformation << std::endl; + sos << "* globalPose:" << endl << getGlobalPose() << std::endl; + std::cout << sos.str(); } // scope1 if (printDecoration) { - cout << "******** End Sensor ********" << endl; + std::cout << "******** End Sensor ********" << std::endl; } if (printChildren) @@ -142,7 +142,7 @@ namespace VirtualRobot if (!result) { - VR_ERROR << "Cloning failed.." << endl; + VR_ERROR << "Cloning failed.." << std::endl; return result; } @@ -197,18 +197,18 @@ namespace VirtualRobot pre += t; } - ss << pre << "<Sensor name='" << name << "'>" << endl; + ss << pre << "<Sensor name='" << name << "'>" << std::endl; std::string pre2 = pre + t; - ss << pre << "<Transform>" << endl; + ss << pre << "<Transform>" << std::endl; ss << BaseIO::toXML(rnTransformation, pre2); - ss << pre << "</Transform>" << endl; + ss << pre << "</Transform>" << std::endl; if (visualizationModel && visualizationModel->getTriMeshModel() && visualizationModel->getTriMeshModel()->faces.size() > 0) { ss << visualizationModel->toXML(modelPath, tabs + 1); } - ss << pre << "</Sensor>" << endl; + ss << pre << "</Sensor>" << std::endl; return ss.str(); } diff --git a/VirtualRobot/Obstacle.cpp b/VirtualRobot/Obstacle.cpp index 34bf986f1632730671d0d2c1f6da77700f2b0c4e..34d8518cbe3049e1f5b8dbf7dd215fad3335ba88 100644 --- a/VirtualRobot/Obstacle.cpp +++ b/VirtualRobot/Obstacle.cpp @@ -75,7 +75,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_ERROR << "Could not create factory for visu type " << visualizationType << endl; + VR_ERROR << "Could not create factory for visu type " << visualizationType << std::endl; return result; } @@ -90,7 +90,7 @@ namespace VirtualRobot if (!visu) { - VR_ERROR << "Could not create box visualization with visu type " << visualizationType << endl; + VR_ERROR << "Could not create box visualization with visu type " << visualizationType << std::endl; return result; } @@ -128,7 +128,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_ERROR << "Could not create factory for visu type " << visualizationType << endl; + VR_ERROR << "Could not create factory for visu type " << visualizationType << std::endl; return result; } @@ -141,7 +141,7 @@ namespace VirtualRobot */ if (!visu) { - VR_ERROR << "Could not create sphere visualization with visu type " << visualizationType << endl; + VR_ERROR << "Could not create sphere visualization with visu type " << visualizationType << std::endl; return result; } @@ -180,7 +180,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_ERROR << "Could not create factory for visu type " << visualizationType << endl; + VR_ERROR << "Could not create factory for visu type " << visualizationType << std::endl; return result; } @@ -193,7 +193,7 @@ namespace VirtualRobot */ if (!visu) { - VR_ERROR << "Could not create cylinder visualization with visu type " << visualizationType << endl; + VR_ERROR << "Could not create cylinder visualization with visu type " << visualizationType << std::endl; return result; } @@ -234,7 +234,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_ERROR << "Could not create factory for visu type " << visualizationType << endl; + VR_ERROR << "Could not create factory for visu type " << visualizationType << std::endl; return result; } @@ -244,7 +244,7 @@ namespace VirtualRobot if (!visu) { - VR_ERROR << "Could not create sphere visualization with visu type " << visualizationType << endl; + VR_ERROR << "Could not create sphere visualization with visu type " << visualizationType << std::endl; return result; } @@ -268,15 +268,15 @@ namespace VirtualRobot { if (printDecoration) { - cout << "**** Obstacle ****" << endl; + std::cout << "**** Obstacle ****" << std::endl; } SceneObject::print(false); - cout << " * id: " << id << endl; + std::cout << " * id: " << id << std::endl; if (printDecoration) { - cout << endl; + std::cout << std::endl; } } @@ -300,7 +300,7 @@ namespace VirtualRobot if (!result) { - VR_ERROR << "Cloning failed.." << endl; + VR_ERROR << "Cloning failed.." << std::endl; return result; } diff --git a/VirtualRobot/Robot.cpp b/VirtualRobot/Robot.cpp index b6ab8d9cc46f732996aa3a5544d8f962d52c64e4..3835f6d56083226b613361aa5f407a66c812c2b9 100644 --- a/VirtualRobot/Robot.cpp +++ b/VirtualRobot/Robot.cpp @@ -70,7 +70,7 @@ namespace VirtualRobot //robotNodeMap.clear(); if (!node) { - VR_WARNING << "NULL root node..." << endl; + VR_WARNING << "NULL root node..." << std::endl; } else { @@ -86,7 +86,7 @@ namespace VirtualRobot if (!this->hasRobotNode(name)) { - VR_WARNING << "Robot node with name <" << name << "> was not registered, adding it to RobotNodeMap" << endl; + VR_WARNING << "Robot node with name <" << name << "> was not registered, adding it to RobotNodeMap" << std::endl; registerRobotNode(allNode); } } @@ -102,7 +102,7 @@ namespace VirtualRobot { if (robotNodeMap.find(robotNodeName) == robotNodeMap.end()) { - VR_WARNING << "No robot node with name <" << robotNodeName << "> defined." << endl; + VR_WARNING << "No robot node with name <" << robotNodeName << "> defined." << std::endl; return RobotNodePtr(); } @@ -188,7 +188,7 @@ namespace VirtualRobot if (robotNodeSetMap.find(nodeSetName) != robotNodeSetMap.end()) { - VR_WARNING << "There are (at least) two robot node sets with name <" << nodeSetName << "> defined, the second one overwrites first definition!" << endl; + VR_WARNING << "There are (at least) two robot node sets with name <" << nodeSetName << "> defined, the second one overwrites first definition!" << std::endl; // overwrite } @@ -307,7 +307,7 @@ namespace VirtualRobot { if (endEffectorMap.find(endEffectorName) == endEffectorMap.end()) { - VR_WARNING << "No endeffector node with name <" << endEffectorName << "> defined." << endl; + VR_WARNING << "No endeffector node with name <" << endEffectorName << "> defined." << std::endl; return EndEffectorPtr(); } @@ -367,47 +367,47 @@ namespace VirtualRobot void Robot::print(bool /*printChildren*/, bool /*printDecoration*/) const { - cout << "******** Robot ********" << endl; - cout << "* Name: " << name << endl; - cout << "* Type: " << type << endl; + std::cout << "******** Robot ********" << std::endl; + std::cout << "* Name: " << name << std::endl; + std::cout << "* Type: " << type << std::endl; if (this->getRootNode()) { - cout << "* Root Node: " << this->getRootNode()->getName() << endl; + std::cout << "* Root Node: " << this->getRootNode()->getName() << std::endl; } else { - cout << "* Root Node: not set" << endl; + std::cout << "* Root Node: not set" << std::endl; } - cout << endl; + std::cout << std::endl; if (this->getRootNode()) { this->getRootNode()->print(true, true); } - cout << endl; + std::cout << std::endl; std::vector<RobotNodeSetPtr> robotNodeSets = this->getRobotNodeSets(); if (robotNodeSets.size() > 0) { - cout << "* RobotNodeSets:" << endl; + std::cout << "* RobotNodeSets:" << std::endl; std::vector<RobotNodeSetPtr>::iterator iter = robotNodeSets.begin(); while (iter != robotNodeSets.end()) { - cout << "----------------------------------" << endl; + std::cout << "----------------------------------" << std::endl; (*iter)->print(); iter++; } - cout << endl; + std::cout << std::endl; } - cout << "******** Robot ********" << endl; + std::cout << "******** Robot ********" << std::endl; } @@ -528,7 +528,7 @@ namespace VirtualRobot auto it = robotNodeSetMap.find(nodeSetName); if (it == robotNodeSetMap.end()) { - VR_WARNING << "No robot node set with name <" << nodeSetName << "> defined." << endl; + VR_WARNING << "No robot node set with name <" << nodeSetName << "> defined." << std::endl; return RobotNodeSetPtr(); } @@ -1001,7 +1001,7 @@ namespace VirtualRobot RobotNodePtr rn = getRobotNode(it->first); if (!rn) { - VR_WARNING << "No joint with name " << it->first << endl; + VR_WARNING << "No joint with name " << it->first << std::endl; } else { @@ -1136,17 +1136,17 @@ namespace VirtualRobot std::string Robot::toXML(const std::string& basePath, const std::string& modelPath /*= "models"*/, bool storeEEF, bool storeRNS, bool storeSensors) { std::stringstream ss; - ss << "<?xml version='1.0' encoding='UTF-8'?>" << endl << endl; - //ss << "<Robot Type='" << this->type << "' RootNode='" << this->getRootNode()->getName() << "' RadianToMMfactor='" << this->radianToMMfactor << "'>" << endl << endl; - ss << "<Robot Type='" << this->type << "' RootNode='" << this->getRootNode()->getName() << "'>" << endl << endl; + ss << "<?xml version='1.0' encoding='UTF-8'?>" << endl << std::endl; + //ss << "<Robot Type='" << this->type << "' RootNode='" << this->getRootNode()->getName() << "' RadianToMMfactor='" << this->radianToMMfactor << "'>" << endl << std::endl; + ss << "<Robot Type='" << this->type << "' RootNode='" << this->getRootNode()->getName() << "'>" << endl << std::endl; std::vector<RobotNodePtr> nodes = getRobotNodes(); for (auto& node : nodes) { - ss << node->toXML(basePath, modelPath, storeSensors) << endl; + ss << node->toXML(basePath, modelPath, storeSensors) << std::endl; } - ss << endl; + ss << std::endl; if (storeRNS) { @@ -1155,12 +1155,12 @@ namespace VirtualRobot for (auto& rn : rns) { - ss << rn->toXML(1) << endl; + ss << rn->toXML(1) << std::endl; } if (rns.size() > 0) { - ss << endl; + ss << std::endl; } } @@ -1170,16 +1170,16 @@ namespace VirtualRobot for (auto& eef : eefs) { - ss << eef->toXML(1) << endl; + ss << eef->toXML(1) << std::endl; } if (eefs.size() > 0) { - ss << endl; + ss << std::endl; } } - ss << "</Robot>" << endl; + ss << "</Robot>" << std::endl; return ss.str(); } diff --git a/VirtualRobot/RobotConfig.cpp b/VirtualRobot/RobotConfig.cpp index b5591c6bbe83c77bcc674dbd82cfee396f96fc77..9a7c8a4643bb7337499f7b3bcca27dd5ec72fb97 100644 --- a/VirtualRobot/RobotConfig.cpp +++ b/VirtualRobot/RobotConfig.cpp @@ -69,11 +69,11 @@ namespace VirtualRobot void RobotConfig::print() const { - cout << " Robot Config <" << name << ">" << endl; + std::cout << " Robot Config <" << name << ">" << std::endl; for (const auto& config : configs) { - cout << " * " << config.first->getName() << ":\t" << config.second << endl; + std::cout << " * " << config.first->getName() << ":\t" << config.second << std::endl; } } @@ -88,7 +88,7 @@ namespace VirtualRobot if (!r) { - VR_WARNING << "Robot is already deleted, skipping update..." << endl; + VR_WARNING << "Robot is already deleted, skipping update..." << std::endl; return false; } @@ -96,7 +96,7 @@ namespace VirtualRobot if (!rn) { - VR_WARNING << "Did not find robot node with name " << node << endl; + VR_WARNING << "Did not find robot node with name " << node << std::endl; return false; } @@ -112,7 +112,7 @@ namespace VirtualRobot if (!r) { - VR_WARNING << "Robot is already deleted, skipping update..." << endl; + VR_WARNING << "Robot is already deleted, skipping update..." << std::endl; return false; } @@ -150,7 +150,7 @@ namespace VirtualRobot if (!rn) { - VR_WARNING << "Could not completely clone RobotConfig " << name << " because new robot does not know a RobotNode with name " << i->first->getName() << endl; + VR_WARNING << "Could not completely clone RobotConfig " << name << " because new robot does not know a RobotNode with name " << i->first->getName() << std::endl; } else { @@ -175,7 +175,7 @@ namespace VirtualRobot if (!r) { - VR_WARNING << "Robot is already deleted, skipping update..." << endl; + VR_WARNING << "Robot is already deleted, skipping update..." << std::endl; return false; } @@ -214,7 +214,7 @@ namespace VirtualRobot if (!r) { - VR_WARNING << "Robot is already deleted..." << endl; + VR_WARNING << "Robot is already deleted..." << std::endl; return 0.0f; } @@ -224,7 +224,7 @@ namespace VirtualRobot if (i == configs.end()) { - VR_ERROR << "Internal error..." << endl; + VR_ERROR << "Internal error..." << std::endl; return 0.0f; } @@ -308,7 +308,7 @@ namespace VirtualRobot if (!r) { - VR_WARNING << "Robot is already deleted, skipping update..." << endl; + VR_WARNING << "Robot is already deleted, skipping update..." << std::endl; return false; } @@ -316,7 +316,7 @@ namespace VirtualRobot if (!rn) { - VR_WARNING << "Did not find robot node with name " << tcpName << endl; + VR_WARNING << "Did not find robot node with name " << tcpName << std::endl; return false; } diff --git a/VirtualRobot/RobotFactory.cpp b/VirtualRobot/RobotFactory.cpp index 34e03e14ebe965edabc2a2f761c52b3921ec5f44..1a0cb6f83ef808beba13e1f6803fbdf84c0fd977 100644 --- a/VirtualRobot/RobotFactory.cpp +++ b/VirtualRobot/RobotFactory.cpp @@ -107,7 +107,7 @@ namespace VirtualRobot { if (!robotNode->getParent() && robotNode != rootNode) { - VR_ERROR << "RobotNode " << robotNode->getName() << " is not connected to kinematic structure..." << endl; + VR_ERROR << "RobotNode " << robotNode->getName() << " is not connected to kinematic structure..." << std::endl; } } @@ -136,7 +136,7 @@ namespace VirtualRobot if (!newRoot) { - VR_ERROR << "No node " << newRootName << endl; + VR_ERROR << "No node " << newRootName << std::endl; } RobotFactory::robotStructureDef newStructure; @@ -231,19 +231,19 @@ namespace VirtualRobot if (!robot->hasRobotNode(startNode)) { - VR_ERROR << "No node with name " << startNode << endl; + VR_ERROR << "No node with name " << startNode << std::endl; return RobotPtr(); } if (!robot->hasRobotNode(endNode)) { - VR_ERROR << "No node with name " << endNode << endl; + VR_ERROR << "No node with name " << endNode << std::endl; return RobotPtr(); } if (!robot->getRobotNode(startNode)->hasChild(endNode, true)) { - VR_ERROR << "No node " << endNode << " is not a child of " << startNode << endl; + VR_ERROR << "No node " << endNode << " is not a child of " << startNode << std::endl; return RobotPtr(); } @@ -260,7 +260,7 @@ namespace VirtualRobot if (!rn) { - VR_ERROR << "No node " << endNode << " is not a child of " << startNode << endl; + VR_ERROR << "No node " << endNode << " is not a child of " << startNode << std::endl; return RobotPtr(); } @@ -299,7 +299,7 @@ namespace VirtualRobot if (robot->hasRobotNode(name)) { - VR_WARNING << "RN with name " << name << " already present" << endl; + VR_WARNING << "RN with name " << name << " already present" << std::endl; return false; } @@ -348,7 +348,7 @@ namespace VirtualRobot if (!robot->hasRobotNode(newStructure.rootName)) { - VR_ERROR << "No root with name " << newStructure.rootName << endl; + VR_ERROR << "No root with name " << newStructure.rootName << std::endl; return RobotPtr(); } @@ -377,7 +377,7 @@ namespace VirtualRobot { if (!robot->hasRobotNode(i.name)) { - VR_ERROR << "Error in parentChildMapping, no node with name " << i.name << endl; + VR_ERROR << "Error in parentChildMapping, no node with name " << i.name << std::endl; return RobotPtr(); } @@ -398,7 +398,7 @@ namespace VirtualRobot if (!robot->hasRobotNode(nodeName)) { - VR_ERROR << "Error in parentChildMapping, no child node with name " << nodeName << endl; + VR_ERROR << "Error in parentChildMapping, no child node with name " << nodeName << std::endl; return RobotPtr(); } @@ -894,7 +894,7 @@ namespace VirtualRobot } else { - cout << "end"; + std::cout << "end"; } RobotNodePtr newNodeFixed = accumulateTransformations(result, nodes[i], newNode, secondNode, currentTrafo); @@ -1007,7 +1007,7 @@ namespace VirtualRobot } else { - VR_INFO << "Skipping node " << i->getName() << endl; + VR_INFO << "Skipping node " << i->getName() << std::endl; } } } diff --git a/VirtualRobot/RobotNodeSet.cpp b/VirtualRobot/RobotNodeSet.cpp index 7cfe7accd1a7507f138da21e4b1fe34db34a1bf1..ea479015963d298e9b9b101351428729d9669927 100644 --- a/VirtualRobot/RobotNodeSet.cpp +++ b/VirtualRobot/RobotNodeSet.cpp @@ -45,14 +45,14 @@ namespace VirtualRobot { VR_WARNING << "RobotNodeSet " << name << " initialized with invalid kinematic root '" << oldRootName << "': Falling back to robot root node '" - << this->kinematicRoot->getName() << "'" << endl; + << this->kinematicRoot->getName() << "'" << std::endl; } else { std::stringstream str; str << "RobotNodeSet " << name << " initialized with invalid kinematic root '" << oldRootName << "': Can't fall back to robot root node (it is null)"; - VR_ERROR << str.str() << endl; + VR_ERROR << str.str() << std::endl; throw std::invalid_argument{str.str()}; } } @@ -72,7 +72,7 @@ namespace VirtualRobot { if (colChecker != cm->getCollisionChecker()) { - VR_WARNING << "col model of " << robotNode->getName() << " belongs to different instance of collision checker, in: " << getName().c_str() << endl; + VR_WARNING << "col model of " << robotNode->getName() << " belongs to different instance of collision checker, in: " << getName().c_str() << std::endl; } else { @@ -95,7 +95,7 @@ namespace VirtualRobot if (robotNodeNames.empty()) { - VR_WARNING << " No robot nodes in set '" << name << "'..." << endl; + VR_WARNING << " No robot nodes in set '" << name << "'..." << std::endl; } else { @@ -155,7 +155,7 @@ namespace VirtualRobot if (robotNodes.empty() || !robotNodes[0]) { - VR_WARNING << " No robot nodes in set '" << name << "'..." << endl; + VR_WARNING << " No robot nodes in set '" << name << "'..." << std::endl; } else { @@ -308,40 +308,40 @@ namespace VirtualRobot void RobotNodeSet::print() const { - cout << " Robot Node Set <" << name << ">" << endl; - cout << " Root node: "; + std::cout << " Robot Node Set <" << name << ">" << std::endl; + std::cout << " Root node: "; if (kinematicRoot) { - cout << kinematicRoot->getName() << endl; + std::cout << kinematicRoot->getName() << std::endl; } else { - cout << "<not set>" << endl; + std::cout << "<not set>" << std::endl; } - cout << " TCP node: "; + std::cout << " TCP node: "; if (tcp) { - cout << tcp->getName() << endl; + std::cout << tcp->getName() << std::endl; } else { - cout << "<not set>" << endl; + std::cout << "<not set>" << std::endl; } for (unsigned int i = 0; i < robotNodes.size(); i++) { - cout << " Node " << i << ": "; + std::cout << " Node " << i << ": "; if (robotNodes[i]) { - cout << robotNodes[i]->getName() << endl; + std::cout << robotNodes[i]->getName() << std::endl; } else { - cout << "<not set>" << endl; + std::cout << "<not set>" << std::endl; } } } @@ -710,7 +710,7 @@ namespace VirtualRobot if (!res && verbose) { - VR_INFO << "RobotNodeSet: " << getName() << ": joint limits are violated" << endl; + VR_INFO << "RobotNodeSet: " << getName() << ": joint limits are violated" << std::endl; } return res; diff --git a/VirtualRobot/RuntimeEnvironment.cpp b/VirtualRobot/RuntimeEnvironment.cpp index 9807c297ce063bc4a662ad18141843e9f3ebadfe..0406e10f39f74937d545faa110950696ffabd702 100644 --- a/VirtualRobot/RuntimeEnvironment.cpp +++ b/VirtualRobot/RuntimeEnvironment.cpp @@ -220,7 +220,7 @@ namespace VirtualRobot // process data-path entries if (vm.count("data-path")) { - //VR_INFO << "Data paths are: " << endl; + //VR_INFO << "Data paths are: " << std::endl; std::vector<std::string> dp = vm["data-path"].as< std::vector< std::string > >(); for (const auto& i : dp) @@ -240,7 +240,7 @@ namespace VirtualRobot if (dp.size() > 1) { - VR_WARNING << "More than one parameter for key '" << key << "'. Using only first one..." << endl; + VR_WARNING << "More than one parameter for key '" << key << "'. Using only first one..." << std::endl; } if (dp.size() > 0) @@ -329,7 +329,7 @@ namespace VirtualRobot if (!quiet) { - VR_ERROR << "Trying to add non-existing data path: " << path << endl; + VR_ERROR << "Trying to add non-existing data path: " << path << std::endl; } return false; @@ -362,12 +362,12 @@ namespace VirtualRobot init(); } - cout << " *********** Simox RuntimeEnvironment ************* " << endl; - cout << "Data paths:" << endl; + std::cout << " *********** Simox RuntimeEnvironment ************* " << std::endl; + std::cout << "Data paths:" << std::endl; for (const auto& dataPath : dataPaths) { - cout << " * " << dataPath << endl; + std::cout << " * " << dataPath << std::endl; } const std::size_t descriptionOffset = std::max( @@ -379,13 +379,13 @@ namespace VirtualRobot { if (items.size() > 0) { - cout << "Known " << name << ":" << endl; + std::cout << "Known " << name << ":" << std::endl; for (const auto& item : items) { - cout << " * " << item.first + std::cout << " * " << item.first << padding(item.first.size(), descriptionOffset) - << item.second << endl; + << item.second << std::endl; } } }; @@ -396,29 +396,29 @@ namespace VirtualRobot if (keyValues.size() > 0) { - cout << "Parsed options:" << endl; + std::cout << "Parsed options:" << std::endl; for (const auto& item : keyValues) { - cout << " * " << item.first << ": " << item.second << endl; + std::cout << " * " << item.first << ": " << item.second << std::endl; } } if (flags.size() > 0) { - cout << "Parsed flags:" << endl; + std::cout << "Parsed flags:" << std::endl; for (const auto& flag : flags) { - cout << " * " << flag << endl; + std::cout << " * " << flag << std::endl; } } if (unrecognizedOptions.size() > 0) { - cout << "Unrecognized options:" << endl; + std::cout << "Unrecognized options:" << std::endl; for (const auto& unrecognizedOption : unrecognizedOptions) { - cout << " * <" << unrecognizedOption << ">" << endl; + std::cout << " * <" << unrecognizedOption << ">" << std::endl; } } } @@ -473,7 +473,7 @@ namespace VirtualRobot if (string[0] != '(' || string[string.length() - 1] != ')') { - VR_WARNING << "Expecting string to start and end with brackets (): " << string << endl; + VR_WARNING << "Expecting string to start and end with brackets (): " << string << std::endl; return false; } @@ -485,7 +485,7 @@ namespace VirtualRobot if (stringSplit.size() != 3) { - VR_WARNING << "Expecting values of string to be separated with a ',': " << string << endl; + VR_WARNING << "Expecting values of string to be separated with a ',': " << string << std::endl; return false; } @@ -506,7 +506,7 @@ namespace VirtualRobot } if (error || boost::math::isinf(a) || boost::math::isinf(-a) || boost::math::isnan(a)) { - VR_WARNING << "Could not convert '" << string << "' to a number." << endl; + VR_WARNING << "Could not convert '" << string << "' to a number." << std::endl; return false; } result(i) = a; @@ -538,7 +538,7 @@ namespace VirtualRobot if (!RuntimeEnvironment::getDataFileAbsolute(s)) { - VR_WARNING << "Could not determine path to file " << standardFilename << endl; + VR_WARNING << "Could not determine path to file " << standardFilename << std::endl; return standardFilename; } diff --git a/VirtualRobot/Scene.cpp b/VirtualRobot/Scene.cpp index 7f49e3da4fec6b9619f52c9c4f1215f8e2534db3..1805a8a223f932311521517b89ca38e2451484ef 100644 --- a/VirtualRobot/Scene.cpp +++ b/VirtualRobot/Scene.cpp @@ -345,7 +345,7 @@ namespace VirtualRobot } } - VR_WARNING << "No robot with name " << name << " registered in scene " << this->name << endl; + VR_WARNING << "No robot with name " << name << " registered in scene " << this->name << std::endl; return RobotPtr(); } @@ -359,7 +359,7 @@ namespace VirtualRobot } } - VR_WARNING << "No obstacle with name " << name << " registered in scene " << this->name << endl; + VR_WARNING << "No obstacle with name " << name << " registered in scene " << this->name << std::endl; return ObstaclePtr(); } @@ -373,7 +373,7 @@ namespace VirtualRobot } } - VR_WARNING << "No Trajectory with name " << name << " registered in scene " << this->name << endl; + VR_WARNING << "No Trajectory with name " << name << " registered in scene " << this->name << std::endl; return TrajectoryPtr(); } @@ -387,7 +387,7 @@ namespace VirtualRobot } } - VR_WARNING << "No ManipulationObject with name " << name << " registered in scene " << this->name << endl; + VR_WARNING << "No ManipulationObject with name " << name << " registered in scene " << this->name << std::endl; return ManipulationObjectPtr(); } @@ -501,7 +501,7 @@ namespace VirtualRobot } } - VR_WARNING << "No robot with name " << robotName << " registered in scene " << this->name << endl; + VR_WARNING << "No robot with name " << robotName << " registered in scene " << this->name << std::endl; return RobotConfigPtr(); } @@ -518,7 +518,7 @@ namespace VirtualRobot } } - VR_WARNING << "No robotConfig with name " << name << " registered for robot " << robot->getName() << " in scene " << this->name << endl; + VR_WARNING << "No robotConfig with name " << name << " registered for robot " << robot->getName() << " in scene " << this->name << std::endl; return RobotConfigPtr(); } @@ -583,7 +583,7 @@ namespace VirtualRobot if (!r) { - VR_ERROR << " no robot with name " << robot << endl; + VR_ERROR << " no robot with name " << robot << std::endl; return RobotNodeSetPtr(); } diff --git a/VirtualRobot/SceneObject.cpp b/VirtualRobot/SceneObject.cpp index 16c2fe396001df30ce34d844e4a073c19b3f64db..3701d0770ec1e78b1dccf4e8a64a011260635b03 100644 --- a/VirtualRobot/SceneObject.cpp +++ b/VirtualRobot/SceneObject.cpp @@ -111,7 +111,7 @@ namespace VirtualRobot if (p) { - VR_ERROR << "Could not set pose of <" << name << ">. The object is attached to <" << p->getName() << ">" << endl; + VR_ERROR << "Could not set pose of <" << name << ">. The object is attached to <" << p->getName() << ">" << std::endl; return; } @@ -201,7 +201,7 @@ namespace VirtualRobot } else { - //VR_WARNING << "<" << name << "> No collision model present ..." << endl; + //VR_WARNING << "<" << name << "> No collision model present ..." << std::endl; return VisualizationNodePtr(); } } @@ -228,7 +228,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_WARNING << "VisualizationFactory of type '" << visualizationType << "' not present. Could not create visualization data in Robot Node <" << name << ">" << endl; + VR_WARNING << "VisualizationFactory of type '" << visualizationType << "' not present. Could not create visualization data in Robot Node <" << name << ">" << std::endl; return false; } @@ -267,7 +267,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_ERROR << " Could not determine a valid VisualizationFactory!!" << endl; + VR_ERROR << " Could not determine a valid VisualizationFactory!!" << std::endl; return; } @@ -340,7 +340,7 @@ namespace VirtualRobot VisualizationNodePtr comModelClone = comModel->clone(); Eigen::Vector3f l = getCoMLocal(); - //cout << "COM:" << l << endl; + //cout << "COM:" << l << std::endl; Eigen::Matrix4f m = Eigen::Matrix4f::Identity(); m.block(0, 3, 3, 1) = l; @@ -360,21 +360,21 @@ namespace VirtualRobot if (enableInertial && visualizationFactory) { // create inertia visu - //cout << "INERTIA MATRIX:" << endl << physics.intertiaMatrix << endl; + //cout << "INERTIA MATRIX:" << endl << physics.intertiaMatrix << std::endl; Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigensolver(physics.inertiaMatrix); if (eigensolver.info() == Eigen::Success) { - /*cout << "The eigenvalues of A are:\n" << eigensolver.eigenvalues() << endl; - cout << "Here's a matrix whose columns are eigenvectors of A \n" + /*cout << "The eigenvalues of A are:\n" << eigensolver.eigenvalues() << std::endl; + std::cout << "Here's a matrix whose columns are eigenvectors of A \n" << "corresponding to these eigenvalues:\n" - << eigensolver.eigenvectors() << endl;*/ + << eigensolver.eigenvectors() << std::endl;*/ //Eigen::Vector3f v1 = eigensolver.eigenvectors().block(0, 0, 3, 1); //Eigen::Vector3f v2 = eigensolver.eigenvectors().block(0, 1, 3, 1); //Eigen::Vector3f v3 = eigensolver.eigenvectors().block(0, 2, 3, 1); - /*cout << "v1:" << v1 << endl; - cout << "v2:" << v2 << endl; - cout << "v3:" << v3 << endl;*/ + /*cout << "v1:" << v1 << std::endl; + std::cout << "v2:" << v2 << std::endl; + std::cout << "v3:" << v3 << std::endl;*/ float xl = static_cast<float>(eigensolver.eigenvalues().rows() > 0 ? eigensolver.eigenvalues()(0) : 1e-6); @@ -455,7 +455,7 @@ namespace VirtualRobot VisualizationNodePtr inertiaVisu = visualizationFactory->createEllipse(xl, yl, zl, true, axesSize, axesSize * 2.0f); Eigen::Vector3f l = getCoMLocal(); - //cout << "COM:" << l << endl; + //cout << "COM:" << l << std::endl; Eigen::Matrix4f m = Eigen::Matrix4f::Identity(); m.block(0, 3, 3, 1) = l; m.block(0, 0, 3, 3) = eigensolver.eigenvectors().block(0, 0, 3, 3); // rotate according to EV @@ -475,7 +475,7 @@ namespace VirtualRobot } else { - VR_INFO << " Could not determine eigenvectors of inertia matrix" << endl; + VR_INFO << " Could not determine eigenvectors of inertia matrix" << std::endl; } } } @@ -699,7 +699,7 @@ namespace VirtualRobot { /*if (!visualizationModel && !collisionModel) { - VR_WARNING << getName() << ": Physics tag CoM is set to eVisuBBoxCenter, but no visualization model is loaded, setting CoM to local position (0/0/0)" << endl; + VR_WARNING << getName() << ": Physics tag CoM is set to eVisuBBoxCenter, but no visualization model is loaded, setting CoM to local position (0/0/0)" << std::endl; } else*/ if (visualizationModel || collisionModel) { @@ -720,7 +720,7 @@ namespace VirtualRobot if (!tm) { - VR_WARNING << "Could not create trimeshmodel for CoM computation, setting CoM to local position (0/0/0)" << endl; + VR_WARNING << "Could not create trimeshmodel for CoM computation, setting CoM to local position (0/0/0)" << std::endl; } else { @@ -804,15 +804,15 @@ namespace VirtualRobot { if (printDecoration) { - cout << "**** SceneObject ****" << endl; + std::cout << "**** SceneObject ****" << std::endl; } - cout << " * Name: " << name << endl; - cout << " * GlobalPose: " << endl << globalPose << endl; + std::cout << " * Name: " << name << std::endl; + std::cout << " * GlobalPose: " << endl << globalPose << std::endl; physics.print(); - cout << " * Visualization:" << endl; + std::cout << " * Visualization:" << std::endl; if (visualizationModel) { @@ -820,21 +820,21 @@ namespace VirtualRobot } else { - cout << "<not set>" << endl; + std::cout << "<not set>" << std::endl; } - cout << " * Update visualization status: "; + std::cout << " * Update visualization status: "; if (updateVisualization) { - cout << "enabled" << endl; + std::cout << "enabled" << std::endl; } else { - cout << "disabled" << endl; + std::cout << "disabled" << std::endl; } - cout << " * Collision Model:" << endl; + std::cout << " * Collision Model:" << std::endl; if (collisionModel) { @@ -842,35 +842,35 @@ namespace VirtualRobot } else { - cout << "<not set>" << endl; + std::cout << "<not set>" << std::endl; } - cout << " * Update collision model status: "; + std::cout << " * Update collision model status: "; if (updateCollisionModel) { - cout << "enabled" << endl; + std::cout << "enabled" << std::endl; } else { - cout << "disabled" << endl; + std::cout << "disabled" << std::endl; } std::vector<SceneObjectPtr> children = this->getChildren(); if (children.size() > 0) { - cout << " * Children:" << endl; + std::cout << " * Children:" << std::endl; for (size_t i = 0; i < children.size(); i++) { - cout << " ** " << children[i]->getName(); + std::cout << " ** " << children[i]->getName(); } } if (printDecoration) { - cout << endl; + std::cout << std::endl; } if (printChildren) @@ -906,7 +906,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_ERROR << " Could not determine a valid VisualizationFactory!!" << endl; + VR_ERROR << " Could not determine a valid VisualizationFactory!!" << std::endl; return; } @@ -978,7 +978,7 @@ namespace VirtualRobot if (!result) { - VR_ERROR << "Cloning failed.." << endl; + VR_ERROR << "Cloning failed.." << std::endl; return result; } @@ -1079,7 +1079,7 @@ namespace VirtualRobot { if (physics.massKg <= 0 && s == SceneObject::Physics::eDynamic) { - VR_WARNING << "Setting simulation type to dynamic, but mass==0, object might be handled as static object by physics engine." << endl; + VR_WARNING << "Setting simulation type to dynamic, but mass==0, object might be handled as static object by physics engine." << std::endl; } physics.simType = s; } @@ -1140,7 +1140,7 @@ namespace VirtualRobot if (!hasChild(child)) { - VR_WARNING << " Trying to detach a not attached object: " << getName() << "->" << child->getName() << endl; + VR_WARNING << " Trying to detach a not attached object: " << getName() << "->" << child->getName() << std::endl; return; } @@ -1154,25 +1154,25 @@ namespace VirtualRobot if (this == child.get()) { - VR_WARNING << "Trying to attach object to it self object! name: " << getName() << endl; + VR_WARNING << "Trying to attach object to it self object! name: " << getName() << std::endl; return false; } if (hasChild(child)) { - VR_WARNING << " Trying to attach already attached object: " << getName() << "->" << child->getName() << endl; + VR_WARNING << " Trying to attach already attached object: " << getName() << "->" << child->getName() << std::endl; return true; // no error } if (child->hasParent()) { - VR_WARNING << " Trying to attach object that has already a parent: " << getName() << "->" << child->getName() << ", child's parent:" << child->getParent()->getName() << endl; + VR_WARNING << " Trying to attach object that has already a parent: " << getName() << "->" << child->getName() << ", child's parent:" << child->getParent()->getName() << std::endl; return false; } if (hasChild(child->getName())) { - VR_ERROR << " Trying to attach object with name: " << child->getName() << " to " << getName() << ", but a child with same name is already present!" << endl; + VR_ERROR << " Trying to attach object with name: " << child->getName() << " to " << getName() << ", but a child with same name is already present!" << std::endl; return false; } @@ -1351,7 +1351,7 @@ namespace VirtualRobot void SceneObject::Physics::print() const { - std::cout << " ** Simulation Type: " << getString(simType) << endl; + std::cout << " ** Simulation Type: " << getString(simType) << std::endl; std::cout << " ** Mass: "; if (massKg <= 0) @@ -1363,7 +1363,7 @@ namespace VirtualRobot std::cout << massKg << " [kg]" << std::endl; } - cout << " ** local CoM [mm] "; + std::cout << " ** local CoM [mm] "; if (comLocation == SceneObject::Physics::eVisuBBoxCenter) { diff --git a/VirtualRobot/SceneObjectSet.cpp b/VirtualRobot/SceneObjectSet.cpp index 00aed81823a740479fcd676b0c9f97725109b2ab..c7f696c46cdcb7d41f5fcdcade303c5c8e2a5a22 100644 --- a/VirtualRobot/SceneObjectSet.cpp +++ b/VirtualRobot/SceneObjectSet.cpp @@ -55,20 +55,20 @@ namespace VirtualRobot { if (!sceneObject) { - VR_WARNING << "NULL data, in: " << name << endl; + VR_WARNING << "NULL data, in: " << name << std::endl; return false; } if (colChecker != sceneObject->getCollisionChecker()) { - VR_WARNING << " col model belongs to different instance of collision checker, in: '" << name << "'" << endl; + VR_WARNING << " col model belongs to different instance of collision checker, in: '" << name << "'" << std::endl; return false; } for (const auto& i : sceneObjects) if (i == sceneObject) { - VR_WARNING << "col model already added, in: " << name << endl; + VR_WARNING << "col model already added, in: " << name << std::endl; return false; } @@ -82,13 +82,13 @@ namespace VirtualRobot { if (!sceneObjectSet) { - VR_WARNING << "NULL data, in: " << getName().c_str() << endl; + VR_WARNING << "NULL data, in: " << getName().c_str() << std::endl; return false; } if (colChecker != sceneObjectSet->getCollisionChecker()) { - VR_WARNING << "col model set belongs to different instance of collision checker, in: " << getName().c_str() << endl; + VR_WARNING << "col model set belongs to different instance of collision checker, in: " << getName().c_str() << std::endl; return false; } @@ -109,7 +109,7 @@ namespace VirtualRobot { if (!robotNodeSet) { - VR_WARNING << "NULL data, in: " << getName().c_str() << endl; + VR_WARNING << "NULL data, in: " << getName().c_str() << std::endl; return false; } @@ -127,7 +127,7 @@ namespace VirtualRobot { if (colChecker != cm->getCollisionChecker()) { - VR_WARNING << "col model of " << robotNode->getName() << " belongs to different instance of collision checker, in: " << getName().c_str() << endl; + VR_WARNING << "col model of " << robotNode->getName() << " belongs to different instance of collision checker, in: " << getName().c_str() << std::endl; } else { @@ -180,7 +180,7 @@ namespace VirtualRobot if (!found) { - VR_WARNING << " col model not added, in: " << name << endl; + VR_WARNING << " col model not added, in: " << name << std::endl; return false; } diff --git a/VirtualRobot/SphereApproximator.cpp b/VirtualRobot/SphereApproximator.cpp index 2519cf8ee9ec294aa18e489885445c9a821634aa..e25a979d8d63de497b1329bab47700c4257beb64 100644 --- a/VirtualRobot/SphereApproximator.cpp +++ b/VirtualRobot/SphereApproximator.cpp @@ -429,7 +429,7 @@ namespace VirtualRobot if (sphereApprox.m_pVisualization) { - cout << __FUNCTION__ << ": Warning: already built a visu, overriding the visualization points..." << endl; + std::cout << __FUNCTION__ << ": Warning: already built a visu, overriding the visualization points..." << std::endl; } Eigen::Vector3f v1,v2,v3; diff --git a/VirtualRobot/TimeOptimalTrajectory/TimeOptimalTrajectory.cpp b/VirtualRobot/TimeOptimalTrajectory/TimeOptimalTrajectory.cpp index b51d10d48630698d4119c0262fbd60a9386b9f81..08ff35b692562832f50d0f044fcfab1ec5a003bc 100644 --- a/VirtualRobot/TimeOptimalTrajectory/TimeOptimalTrajectory.cpp +++ b/VirtualRobot/TimeOptimalTrajectory/TimeOptimalTrajectory.cpp @@ -95,16 +95,16 @@ namespace VirtualRobot double maxVelocity = getAccelerationMaxPathVelocity(s); if(maxVelocity == numeric_limits<double>::infinity()) maxVelocity = 10.0; - file1 << s << " " << maxVelocity << " " << getVelocityMaxPathVelocity(s) << endl; + file1 << s << " " << maxVelocity << " " << getVelocityMaxPathVelocity(s) << std::endl; } file1.close(); ofstream file2("trajectory.txt"); for(const auto & it : trajectory) { - file2 << it.pathPos << " " << it.pathVel << endl; + file2 << it.pathPos << " " << it.pathVel << std::endl; } for(const auto & it : endTrajectory) { - file2 << it.pathPos << " " << it.pathVel << endl; + file2 << it.pathPos << " " << it.pathVel << std::endl; } file2.close(); } @@ -255,7 +255,7 @@ namespace VirtualRobot } else if(pathVel < 0.0) { valid = false; - cout << "error" << endl; + std::cout << "error" << std::endl; return true; } @@ -334,7 +334,7 @@ namespace VirtualRobot if(pathVel < 0.0) { valid = false; - cout << "Error while integrating backward: Negative path velocity" << endl; + std::cout << "Error while integrating backward: Negative path velocity" << std::endl; endTrajectory = trajectory; return; } @@ -357,7 +357,7 @@ namespace VirtualRobot } valid = false; - cout << "Error while integrating backward: Did not hit start trajectory" << endl; + std::cout << "Error while integrating backward: Did not hit start trajectory" << std::endl; endTrajectory = trajectory; } diff --git a/VirtualRobot/Trajectory.cpp b/VirtualRobot/Trajectory.cpp index 8ff0825c37931d98f8bfdd40eae8af1773869e34..791fc268b316886e173445eeb9e10a334bf501e6 100644 --- a/VirtualRobot/Trajectory.cpp +++ b/VirtualRobot/Trajectory.cpp @@ -207,7 +207,7 @@ namespace VirtualRobot { if (!trajectoryToInsert) { - VR_ERROR << "null data" << endl; + VR_ERROR << "null data" << std::endl; return; } @@ -424,7 +424,7 @@ namespace VirtualRobot void Trajectory::print() const { std::string s = toXML(0); - VR_INFO << s << endl; + VR_INFO << s << std::endl; } std::string Trajectory::getName() const @@ -452,7 +452,7 @@ namespace VirtualRobot if (!visualizationFactory) { - VR_ERROR << "Could not create factory for visu type " << visualizationFactoryName << endl; + VR_ERROR << "Could not create factory for visu type " << visualizationFactoryName << std::endl; return VisualizationNodePtr(); } diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.cpp index df4c91f161a54ecd72a67b4d5baeb054c2c3b0c0..c7b3820fb322ef95f8fd1d7da6311cea293310d2 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.cpp +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualization.cpp @@ -106,7 +106,7 @@ namespace VirtualRobot { if (which >= visualizationNodes.size()) { - VR_WARNING << "Could not find visualizationNode..." << endl; + VR_WARNING << "Could not find visualizationNode..." << std::endl; return false; } @@ -142,7 +142,7 @@ namespace VirtualRobot if (!isVisualizationNodeRegistered(visualizationNode)) { - VR_WARNING << "Could not find visualizationNode..." << endl; + VR_WARNING << "Could not find visualizationNode..." << std::endl; return false; } diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp index 9293fa7f9316156a0479c7f5230a1d8bf67eaf29..b8a7ddf97e2467b09e9f2322c0a5a36aacea3f14 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp @@ -243,7 +243,7 @@ namespace VirtualRobot { if (scaleX != 1.0f || scaleY != 1.0f || scaleZ != 1.0f) { - VR_WARNING << "Scaling not yet supported for Coin3D files" << endl; + VR_WARNING << "Scaling not yet supported for Coin3D files" << std::endl; } return getVisualizationFromCoin3DFile(filename, boundingBox); @@ -286,7 +286,7 @@ namespace VirtualRobot if (!readOK) { - VR_ERROR << "Could not read file with assimp: " << filename << endl; + VR_ERROR << "Could not read file with assimp: " << filename << std::endl; return visualizationNode; } @@ -303,7 +303,7 @@ namespace VirtualRobot if (scaleX != 1.0f || scaleY != 1.0f || scaleZ != 1.0f) { - VR_WARNING << "Scaling not yet supported" << endl; + VR_WARNING << "Scaling not yet supported" << std::endl; } // passing an empty string to SoInput and trying to open it aborts the program @@ -422,7 +422,7 @@ namespace VirtualRobot //boxAction.getXfBoundingBox().getBounds(minX, minY, minZ, maxX, maxY, maxZ); boxAction.getBoundingBox().getBounds(minX, minY, minZ, maxX, maxY, maxZ); - cout << "x: " << minX << "," << maxX << " ; Y: " << minY << "," << maxY << " ; Z: " << minZ << "," << maxZ << endl; + std::cout << "x: " << minX << "," << maxX << " ; Y: " << minY << "," << maxY << " ; Z: " << minZ << "," << maxZ << std::endl; SoCube* cu = new SoCube(); @@ -1800,17 +1800,17 @@ namespace VirtualRobot if (fabs(normal1.norm() - 1.0f) > 1.1) { - VR_ERROR << "Wrong normal, norm:" << normal1.norm() << endl; + VR_ERROR << "Wrong normal, norm:" << normal1.norm() << std::endl; } if (fabs(normal2.norm() - 1.0f) > 1.1) { - VR_ERROR << "Wrong normal, norm:" << normal2.norm() << endl; + VR_ERROR << "Wrong normal, norm:" << normal2.norm() << std::endl; } if (fabs(normal3.norm() - 1.0f) > 1.1) { - VR_ERROR << "Wrong normal, norm:" << normal3.norm() << endl; + VR_ERROR << "Wrong normal, norm:" << normal3.norm() << std::endl; } SoMatrixTransform* mt1 = new SoMatrixTransform; @@ -2078,7 +2078,7 @@ namespace VirtualRobot if (!tcp) { - VR_ERROR << " No tcp in eef " << eef->getName() << endl; + VR_ERROR << " No tcp in eef " << eef->getName() << std::endl; ok = false; } } @@ -3408,7 +3408,7 @@ namespace VirtualRobot if (d.maxCoeff() > 1.0f) { - VR_ERROR << "Maximal coefficient must not be >1!" << endl; + VR_ERROR << "Maximal coefficient must not be >1!" << std::endl; } SoDrawStyle* ds = new SoDrawStyle; @@ -3527,7 +3527,7 @@ namespace VirtualRobot if (d.maxCoeff() > 1.0f) { - VR_ERROR << "Maximal coefficient must not be >1!" << endl; + VR_ERROR << "Maximal coefficient must not be >1!" << std::endl; } SoDrawStyle* ds = new SoDrawStyle; @@ -3636,7 +3636,7 @@ namespace VirtualRobot { if (!camNode) { - VR_ERROR << "No cam node to render..." << endl; + VR_ERROR << "No cam node to render..." << std::endl; return false; } @@ -3702,7 +3702,7 @@ namespace VirtualRobot root->addChild(camInMeters); root->addChild(scene); - //VR_INFO << "*** preRender took " << (SbTime::getTimeOfDay() - t1).getValue() * 1000 << " ms" << endl; + //VR_INFO << "*** preRender took " << (SbTime::getTimeOfDay() - t1).getValue() * 1000 << " ms" << std::endl; SbTime t = SbTime::getTimeOfDay(); // for profiling bool ok = renderer->render(root) == TRUE ? true : false; @@ -3711,7 +3711,7 @@ namespace VirtualRobot float msec = (SbTime::getTimeOfDay() - t).getValue() * 1000; if (msec > 300) { - VR_WARNING << "************ offscreen rendering took " << msec << " ms" << endl; + VR_WARNING << "************ offscreen rendering took " << msec << " ms" << std::endl; } root->unref(); @@ -3722,7 +3722,7 @@ namespace VirtualRobot { if (!renderErrorPrinted) { - VR_ERROR << "Rendering not successful! This error is printed only once." << endl; + VR_ERROR << "Rendering not successful! This error is printed only once." << std::endl; renderErrorPrinted = true; } @@ -3735,7 +3735,7 @@ namespace VirtualRobot float msec2 = (SbTime::getTimeOfDay() - t2a).getValue() * 1000; if (msec2 > 300) { - VR_WARNING << "************ getBuffer took " << msec2 << " ms" << endl; + VR_WARNING << "************ getBuffer took " << msec2 << " ms" << std::endl; } return true; } @@ -3803,7 +3803,7 @@ namespace VirtualRobot //check input if (!camNode) { - VR_ERROR << "No cam node to render..." << endl; + VR_ERROR << "No cam node to render..." << std::endl; return false; } return renderOffscreenRgbDepthPointcloud( @@ -3824,17 +3824,17 @@ namespace VirtualRobot { if (!offscreenRenderer) { - VR_ERROR << "No renderer..." << endl; + VR_ERROR << "No renderer..." << std::endl; return false; } if (!scene) { - VR_ERROR << "No scene to render..." << endl; + VR_ERROR << "No scene to render..." << std::endl; return false; } if (width <= 0 || height <= 0) { - VR_ERROR << "Invalid image dimensions..." << endl; + VR_ERROR << "Invalid image dimensions..." << std::endl; return false; } //setup @@ -3893,7 +3893,7 @@ namespace VirtualRobot { if (!renderErrorPrinted) { - VR_ERROR << "Rendering not successful! This error is printed only once." << endl; + VR_ERROR << "Rendering not successful! This error is printed only once." << std::endl; renderErrorPrinted = true; } return false; @@ -4043,7 +4043,7 @@ namespace VirtualRobot if (visualizations[i]->getType() != getName()) { - VR_ERROR << "Skipping Visualization " << i << ": Is type " << visualizations[i]->getType() << ", but factory is of type " << getName() << endl; + VR_ERROR << "Skipping Visualization " << i << ": Is type " << visualizations[i]->getType() << ", but factory is of type " << getName() << std::endl; continue; } @@ -4060,7 +4060,7 @@ namespace VirtualRobot } else { - VR_WARNING << "Invalid type casting to CoinVisualizationNode?!" << endl; + VR_WARNING << "Invalid type casting to CoinVisualizationNode?!" << std::endl; } } @@ -4305,7 +4305,7 @@ namespace VirtualRobot if (o->getType() != getName()) { - VR_ERROR << "Skipping Visualization type " << o->getType() << ", but factory is of type " << getName() << endl; + VR_ERROR << "Skipping Visualization type " << o->getType() << ", but factory is of type " << getName() << std::endl; return; } @@ -4330,7 +4330,7 @@ namespace VirtualRobot } else { - VR_WARNING << "Invalid type casting to CoinVisualizationNode?!" << endl; + VR_WARNING << "Invalid type casting to CoinVisualizationNode?!" << std::endl; } } diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp index 87461abce49f6d66c6eeb362fa1c339de49d43e3..3131dee50a4701f9ced7f02c7b704b149e096ff2 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp @@ -61,7 +61,7 @@ namespace VirtualRobot if (!visualization) { - cout << "dummy node created" << endl; + std::cout << "dummy node created" << std::endl; visualization = new SoSeparator(); // create dummy node } @@ -191,7 +191,7 @@ namespace VirtualRobot TriMeshModel* triangleMeshModel = static_cast<TriMeshModel*>(data); if (!triangleMeshModel) { - VR_INFO << ": Internal error, NULL data" << endl; + VR_INFO << ": Internal error, NULL data" << std::endl; return; } @@ -252,7 +252,7 @@ namespace VirtualRobot void CoinVisualizationNode::print() { - cout << " CoinVisualization: "; + std::cout << " CoinVisualization: "; if (!triMeshModel) { @@ -266,20 +266,20 @@ namespace VirtualRobot if (triMeshModel->faces.size() > 0) { - cout << triMeshModel->faces.size() << " triangles" << endl;// Extend: " << ma[0]-mi[0] << ", " << ma[1] - mi[1] << ", " << ma[2] - mi[2] << endl; + std::cout << triMeshModel->faces.size() << " triangles" << std::endl;// Extend: " << ma[0]-mi[0] << ", " << ma[1] - mi[1] << ", " << ma[2] - mi[2] << std::endl; triMeshModel->getSize(mi, ma); - cout << " Min point: (" << mi[0] << "," << mi[1] << "," << mi[2] << ")" << endl; - cout << " Max point: (" << ma[0] << "," << ma[1] << "," << ma[2] << ")" << endl; + std::cout << " Min point: (" << mi[0] << "," << mi[1] << "," << mi[2] << ")" << std::endl; + std::cout << " Max point: (" << ma[0] << "," << ma[1] << "," << ma[2] << ")" << std::endl; } else { - cout << "No model" << endl; + std::cout << "No model" << std::endl; } } else { - cout << "No model" << endl; + std::cout << "No model" << std::endl; } } @@ -450,7 +450,7 @@ namespace VirtualRobot { if (!std::filesystem::create_directories(completePath)) { - VR_ERROR << "Could not create model dir " << completePath.string() << endl; + VR_ERROR << "Could not create model dir " << completePath.string() << std::endl; return false; } } @@ -461,7 +461,7 @@ namespace VirtualRobot if (!so->openFile(completeFile.string().c_str())) { - VR_ERROR << "Could not open file " << completeFile.string() << " for writing." << endl; + VR_ERROR << "Could not open file " << completeFile.string() << " for writing." << std::endl; } std::filesystem::path extension = completeFile.extension(); diff --git a/VirtualRobot/Visualization/TriMeshModel.cpp b/VirtualRobot/Visualization/TriMeshModel.cpp index 87f6452d427fefcff667c02b340d66b21c5fcea2..79f52b0858c1d9d084e3f42e595270d02fad8983 100644 --- a/VirtualRobot/Visualization/TriMeshModel.cpp +++ b/VirtualRobot/Visualization/TriMeshModel.cpp @@ -883,40 +883,40 @@ namespace VirtualRobot void TriMeshModel::print() { - cout << "TriMeshModel\nNr of Faces:" << faces.size() << "\nNr of vertices:" << vertices.size() << endl; + std::cout << "TriMeshModel\nNr of Faces:" << faces.size() << "\nNr of vertices:" << vertices.size() << std::endl; boundingBox.print(); } void TriMeshModel::printNormals() { - cout << "TriMeshModel Normals:" << endl; + std::cout << "TriMeshModel Normals:" << std::endl; std::streamsize pr = cout.precision(2); for (auto& face : faces) { - cout << "<" << face.normal(0) << "," << face.normal(1) << "," << face.normal(2) << ">,"; + std::cout << "<" << face.normal(0) << "," << face.normal(1) << "," << face.normal(2) << ">,"; } cout.precision(pr); } void TriMeshModel::printVertices() { - cout << "TriMeshModel Vertices:" << endl; + std::cout << "TriMeshModel Vertices:" << std::endl; std::streamsize pr = cout.precision(2); for (size_t i = 0; i < vertices.size(); i++) { - cout << vertices[i].transpose() << endl; + std::cout << vertices[i].transpose() << std::endl; } cout.precision(pr); } void TriMeshModel::printFaces() { - cout << "TriMeshModel Faces (vertex indices):" << endl; + std::cout << "TriMeshModel Faces (vertex indices):" << std::endl; std::streamsize pr = cout.precision(2); for (auto& face : faces) { - cout << face.id1 << "," << face.id2 << "," << face.id3 << endl; + std::cout << face.id1 << "," << face.id2 << "," << face.id3 << std::endl; } cout.precision(pr); } diff --git a/VirtualRobot/Visualization/VisualizationNode.cpp b/VirtualRobot/Visualization/VisualizationNode.cpp index 2ef58ef40eaa86e0ef50a7896b4a1da2f0f91b87..82866aa9685800563572316414173a3eb040f8f2 100644 --- a/VirtualRobot/Visualization/VisualizationNode.cpp +++ b/VirtualRobot/Visualization/VisualizationNode.cpp @@ -129,7 +129,7 @@ namespace VirtualRobot void VisualizationNode::print() { - cout << "Dummy VisualizationNode" << endl; + std::cout << "Dummy VisualizationNode" << std::endl; } void VisualizationNode::setupVisualization(bool showVisualization, bool showAttachedVisualizations) @@ -240,7 +240,7 @@ namespace VirtualRobot if (i == visualizations.end()) { - VR_ERROR << "Could not find visualization factory. Aborting..." << endl; + VR_ERROR << "Could not find visualization factory. Aborting..." << std::endl; return VisualizationNodePtr(); } @@ -272,7 +272,7 @@ namespace VirtualRobot { if (!std::filesystem::create_directories(completePath)) { - VR_ERROR << "Could not create model dir " << completePath.string() << endl; + VR_ERROR << "Could not create model dir " << completePath.string() << std::endl; return false; } } diff --git a/VirtualRobot/Workspace/Manipulability.cpp b/VirtualRobot/Workspace/Manipulability.cpp index 8c8dce689ca737408021f742e3009b4540a4e8de..6b417e77f19dc40cd10eddbb758c1c8bba842d8c 100644 --- a/VirtualRobot/Workspace/Manipulability.cpp +++ b/VirtualRobot/Workspace/Manipulability.cpp @@ -79,7 +79,7 @@ namespace VirtualRobot { if (mSc > 1.05) { - VR_WARNING << "Manipulability is larger than max value. Current Manip:" << m << ", maxManip:" << maxManip << ", percent:" << mSc << endl; + VR_WARNING << "Manipulability is larger than max value. Current Manip:" << m << ", maxManip:" << maxManip << ", percent:" << mSc << std::endl; } mSc = 1.0f; @@ -192,29 +192,29 @@ namespace VirtualRobot if (!lOK) { - VR_ERROR << "Could not get manip measure name from file?!" << endl; + VR_ERROR << "Could not get manip measure name from file?!" << std::endl; return false; } if (measure && (res != measure->getName())) { - VR_WARNING << "Different manipulability measure implementations!" << endl; - cout << "Manip File :" << res << endl; - cout << "Instance:" << measure->getName() << endl; - cout << "-> This may cause problems if you intend to extend the manipulability representation." << endl; - cout << "-> Otherwise you can ignore this warning." << endl; + VR_WARNING << "Different manipulability measure implementations!" << std::endl; + std::cout << "Manip File :" << res << std::endl; + std::cout << "Instance:" << measure->getName() << std::endl; + std::cout << "-> This may cause problems if you intend to extend the manipulability representation." << std::endl; + std::cout << "-> Otherwise you can ignore this warning." << std::endl; } measureName = res; if (!measure && measureName == PoseQualityManipulability::getTypeName()) { - VR_INFO << "Creating manipulability measure" << endl; + VR_INFO << "Creating manipulability measure" << std::endl; measure.reset(new PoseQualityManipulability(nodeSet)); } else if (!measure && measureName == PoseQualityExtendedManipulability::getTypeName()) { - VR_INFO << "Creating extended manipulability measure" << endl; + VR_INFO << "Creating extended manipulability measure" << std::endl; measure.reset(new PoseQualityExtendedManipulability(nodeSet)); } @@ -258,7 +258,7 @@ namespace VirtualRobot if (!sd1 || !sd2) { - VR_ERROR << "Could not get rns for self dist name from file?!" << endl; + VR_ERROR << "Could not get rns for self dist name from file?!" << std::endl; return false; } @@ -269,14 +269,14 @@ namespace VirtualRobot if (!selfDistStatic) { - VR_ERROR << " No rns with name " << selfDist1 << " found..." << endl; + VR_ERROR << " No rns with name " << selfDist1 << " found..." << std::endl; considerSelfDist = false; selfDistDynamic.reset(); } if (!selfDistDynamic) { - VR_ERROR << " No rns with name " << selfDist2 << " found..." << endl; + VR_ERROR << " No rns with name " << selfDist2 << " found..." << std::endl; considerSelfDist = false; selfDistStatic.reset(); } @@ -297,7 +297,7 @@ namespace VirtualRobot PoseQualityExtendedManipulabilityPtr pqm = std::dynamic_pointer_cast<PoseQualityExtendedManipulability>(measure); if (pqm) { - VR_INFO << "Setting up self dist, alpha:" << selfDistAlpha << ", beta:" << selfDistBeta << endl; + VR_INFO << "Setting up self dist, alpha:" << selfDistAlpha << ", beta:" << selfDistBeta << std::endl; pqm->considerObstacles(true, selfDistAlpha, selfDistBeta); } } @@ -405,30 +405,30 @@ namespace VirtualRobot void Manipulability::customPrint() { - cout << "Manipulability Measure: " << measureName << endl; - cout << "Considered Joint Limits:"; + std::cout << "Manipulability Measure: " << measureName << std::endl; + std::cout << "Considered Joint Limits:"; if (considerJL) { - cout << " yes" << endl; + std::cout << " yes" << std::endl; } else { - cout << " no" << endl; + std::cout << " no" << std::endl; } - cout << "Maximal manipulability (as defined on construction):" << maxManip << endl; - cout << "Considered Self-Distance:"; + std::cout << "Maximal manipulability (as defined on construction):" << maxManip << std::endl; + std::cout << "Considered Self-Distance:"; if (considerSelfDist && selfDistStatic && selfDistDynamic) { - cout << " yes" << endl; - cout << " - Self Dist Col Model Static:" << selfDistStatic->getName() << endl; - cout << " - Self Dist Col Model Dynamic:" << selfDistDynamic->getName() << endl; + std::cout << " yes" << std::endl; + std::cout << " - Self Dist Col Model Static:" << selfDistStatic->getName() << std::endl; + std::cout << " - Self Dist Col Model Dynamic:" << selfDistDynamic->getName() << std::endl; } else { - cout << " no" << endl; + std::cout << " no" << std::endl; } } @@ -436,7 +436,7 @@ namespace VirtualRobot { if (!measure) { - VR_INFO << "Creating manipulability measure" << endl; + VR_INFO << "Creating manipulability measure" << std::endl; measure.reset(new PoseQualityManipulability(nodeSet)); measureName = measure->getName(); } @@ -453,7 +453,7 @@ namespace VirtualRobot { if (!data) { - VR_ERROR << "NULL DATA" << endl; + VR_ERROR << "NULL DATA" << std::endl; return 0.0f; } @@ -481,7 +481,7 @@ namespace VirtualRobot if (!measure) { - VR_WARNING << "No manipulability measure given?!" << endl; + VR_WARNING << "No manipulability measure given?!" << std::endl; storeMaxManipulability = 1.0f; return true; } @@ -518,7 +518,7 @@ namespace VirtualRobot if (storeMaxManipulability == 0.0f) { - VR_ERROR << "Maximum manipulability == 0 ??" << endl; + VR_ERROR << "Maximum manipulability == 0 ??" << std::endl; storeMaxManipulability = 1.0f; return false; } @@ -598,7 +598,7 @@ namespace VirtualRobot for (int a = s; a < (int)data->getSize(0) - s; a++) { - cout << "#"; + std::cout << "#"; for (int b = s; b < (int)data->getSize(1) - s; b++) { diff --git a/VirtualRobot/Workspace/VoxelTreeND.hpp b/VirtualRobot/Workspace/VoxelTreeND.hpp index 3aa640a9b83846dfff95ebeb3eab7ab58b3f86a0..c12264c9917b27c9fe251f165ae684dbb5cf2ba3 100644 --- a/VirtualRobot/Workspace/VoxelTreeND.hpp +++ b/VirtualRobot/Workspace/VoxelTreeND.hpp @@ -58,7 +58,7 @@ namespace VirtualRobot unsigned char *e = v.getEntry(pos); // check if entry is set if (e) - cout << "Entry is set:" << *e << endl; + std::cout << "Entry is set:" << *e << std::endl; */ template <typename T, unsigned int N> @@ -345,7 +345,7 @@ namespace VirtualRobot bzip2->read((void*)(&(d.level)),dataSize,n); if (n!=dataSize) { - VR_ERROR << "Invalid number of bytes?!" << endl; + VR_ERROR << "Invalid number of bytes?!" << std::endl; bzip2->close(); file.close(); delete tree; @@ -356,7 +356,7 @@ namespace VirtualRobot bzip2->read((void*)(&(d.pos[0])),dataSize,n); if (n!=dataSize) { - VR_ERROR << "Invalid number of bytes?!" << endl; + VR_ERROR << "Invalid number of bytes?!" << std::endl; bzip2->close(); file.close(); delete tree; @@ -367,7 +367,7 @@ namespace VirtualRobot bzip2->read((void*)(&(d.extends[0])),dataSize,n); if (n!=dataSize) { - VR_ERROR << "Invalid number of bytes?!" << endl; + VR_ERROR << "Invalid number of bytes?!" << std::endl; bzip2->close(); file.close(); delete tree; @@ -687,7 +687,7 @@ namespace VirtualRobot VoxelTreeNDElement<T, N>* getNextElement() { #ifdef VoxelTreeND_DEBUG_OUTPUT - cout << "current stack:" << endl; + std::cout << "current stack:" << std::endl; printStack(); #endif @@ -748,7 +748,7 @@ namespace VirtualRobot } #ifdef VoxelTreeND_DEBUG_OUTPUT - cout << "new stack:" << endl; + std::cout << "new stack:" << std::endl; printStack(); #endif return currentElement; diff --git a/VirtualRobot/Workspace/VoxelTreeNDElement.hpp b/VirtualRobot/Workspace/VoxelTreeNDElement.hpp index 15d208192caaab599d73272faffe6343a9890cad..94a294391679b938d0df5763c3a02e013a1bc2cd 100644 --- a/VirtualRobot/Workspace/VoxelTreeNDElement.hpp +++ b/VirtualRobot/Workspace/VoxelTreeNDElement.hpp @@ -95,7 +95,7 @@ namespace VirtualRobot } #ifdef VoxelTreeNDElement_DEBUG_OUTPUT - cout << "[" << level << "]"; + std::cout << "[" << level << "]"; #endif if (leaf || level >= (tree->getMaxLevels() - 1)) @@ -104,7 +104,7 @@ namespace VirtualRobot delete entry; entry = new T(e); #ifdef VoxelTreeNDElement_DEBUG_OUTPUT - cout << ":" << e; + std::cout << ":" << e; #endif return true; } @@ -475,7 +475,7 @@ namespace VirtualRobot } #ifdef VoxelTreeNDElement_DEBUG_OUTPUT - cout << "->" << indx << "->"; + std::cout << "->" << indx << "->"; #endif if (children[indx]) diff --git a/VirtualRobot/Workspace/WorkspaceDataArray.cpp b/VirtualRobot/Workspace/WorkspaceDataArray.cpp index 3af2531746652127a8054de8838395e5c7bb799f..990c239521a2c37f2f11f671cf6b5d6e988a1662 100644 --- a/VirtualRobot/Workspace/WorkspaceDataArray.cpp +++ b/VirtualRobot/Workspace/WorkspaceDataArray.cpp @@ -28,7 +28,7 @@ namespace VirtualRobot if (sizeRot > UINT_MAX || sizeTr > UINT_MAX) { - VR_ERROR << "Could not assign " << sizeRot << " bytes of memory (>UINT_MAX). Reduce size of reachability space..." << endl; + VR_ERROR << "Could not assign " << sizeRot << " bytes of memory (>UINT_MAX). Reduce size of reachability space..." << std::endl; } try @@ -48,12 +48,12 @@ namespace VirtualRobot } catch (const std::exception& e) { - VR_ERROR << "Exception: " << e.what() << endl << "Could not assign " << sizeRot << " bytes of memory. Reduce size of reachability space..." << endl; + VR_ERROR << "Exception: " << e.what() << endl << "Could not assign " << sizeRot << " bytes of memory. Reduce size of reachability space..." << std::endl; throw; } catch (...) { - VR_ERROR << "Could not assign " << sizeRot << " bytes of memory. Reduce size of reachability space..." << endl; + VR_ERROR << "Could not assign " << sizeRot << " bytes of memory. Reduce size of reachability space..." << std::endl; throw; } @@ -81,7 +81,7 @@ namespace VirtualRobot if (sizeRot > UINT_MAX || sizeTr > UINT_MAX) { - VR_ERROR << "Could not assign " << sizeRot << " bytes of memory (>UINT_MAX). Reduce size of reachability space..." << endl; + VR_ERROR << "Could not assign " << sizeRot << " bytes of memory (>UINT_MAX). Reduce size of reachability space..." << std::endl; } try @@ -111,12 +111,12 @@ namespace VirtualRobot } catch (const std::exception& e) { - VR_ERROR << "Exception: " << e.what() << endl << "Could not assign " << sizeRot << " bytes of memory. Reduce size of reachability space..." << endl; + VR_ERROR << "Exception: " << e.what() << endl << "Could not assign " << sizeRot << " bytes of memory. Reduce size of reachability space..." << std::endl; throw; } catch (...) { - VR_ERROR << "Could not assign " << sizeRot << " bytes of memory. Reduce size of reachability space..." << endl; + VR_ERROR << "Could not assign " << sizeRot << " bytes of memory. Reduce size of reachability space..." << std::endl; throw; } @@ -562,7 +562,7 @@ namespace VirtualRobot if (!bzip2->write(dataBlock, blockSize)) { - VR_ERROR << "Error writing to file.." << endl; + VR_ERROR << "Error writing to file.." << std::endl; bzip2->close(); file.close(); return false; diff --git a/VirtualRobot/Workspace/WorkspaceGrid.cpp b/VirtualRobot/Workspace/WorkspaceGrid.cpp index d322e388814f8394458725ae0ad5875262ce8b8c..62371f9ea66aa5df294dbf1675581d892be4ad50 100644 --- a/VirtualRobot/Workspace/WorkspaceGrid.cpp +++ b/VirtualRobot/Workspace/WorkspaceGrid.cpp @@ -39,7 +39,7 @@ namespace VirtualRobot THROW_VR_EXCEPTION("ERROR negative grid size"); } - VR_INFO << ": creating grid with " << gridSizeX << "x" << gridSizeY << " = " << gridSizeX* gridSizeY << " entries" << endl; + VR_INFO << ": creating grid with " << gridSizeX << "x" << gridSizeY << " = " << gridSizeX* gridSizeY << " entries" << std::endl; data = new int[gridSizeX * gridSizeY]; graspLink = new std::vector<GraspPtr>[gridSizeX * gridSizeY]; memset(data, 0, sizeof(int)*gridSizeX * gridSizeY); @@ -70,7 +70,7 @@ namespace VirtualRobot if (nPosX < 0 || nPosY < 0 || nPosX >= gridSizeX || nPosY >= gridSizeY) { - //cout << __PRETTY_FUNCTION__ << " internal error: " << fX << "," << fY << endl; + //cout << __PRETTY_FUNCTION__ << " internal error: " << fX << "," << fY << std::endl; return 0; } @@ -89,7 +89,7 @@ namespace VirtualRobot if (nPosX < 0 || nPosY < 0 || nPosX >= gridSizeX || nPosY >= gridSizeY) { - //cout << __PRETTY_FUNCTION__ << " internal error: " << fX << "," << fY << endl; + //cout << __PRETTY_FUNCTION__ << " internal error: " << fX << "," << fY << std::endl; return false; } @@ -120,7 +120,7 @@ namespace VirtualRobot if (nPosX < 0 || nPosY < 0 || nPosX >= gridSizeX || nPosY >= gridSizeY) { - //cout << __PRETTY_FUNCTION__ << " internal error: " << fX << "," << fY << endl; + //cout << __PRETTY_FUNCTION__ << " internal error: " << fX << "," << fY << std::endl; return false; } @@ -138,7 +138,7 @@ namespace VirtualRobot if (cellX < 0 || cellY < 0 || cellX >= gridSizeX || cellY >= gridSizeY) { - //cout << __PRETTY_FUNCTION__ << " internal error: " << nX << "," << nY << endl; + //cout << __PRETTY_FUNCTION__ << " internal error: " << nX << "," << nY << std::endl; return 0; } @@ -154,7 +154,7 @@ namespace VirtualRobot if (cellX < 0 || cellY < 0 || cellX >= gridSizeX || cellY >= gridSizeY) { - //cout << __PRETTY_FUNCTION__ << " internal error: " << nX << "," << nY << endl; + //cout << __PRETTY_FUNCTION__ << " internal error: " << nX << "," << nY << std::endl; return false; } @@ -182,7 +182,7 @@ namespace VirtualRobot if (cellX < 0 || cellY < 0 || cellX >= gridSizeX || cellY >= gridSizeY) { - //cout << __PRETTY_FUNCTION__ << " internal error: " << nX << "," << nY << endl; + //cout << __PRETTY_FUNCTION__ << " internal error: " << nX << "," << nY << std::endl; return false; } @@ -212,7 +212,7 @@ namespace VirtualRobot if (cellX < 0 || cellY < 0 || cellX >= gridSizeX || cellY >= gridSizeY) { - //cout << __PRETTY_FUNCTION__ << " internal error: " << nPosX << "," << nPosY << endl; + //cout << __PRETTY_FUNCTION__ << " internal error: " << nPosX << "," << nPosY << std::endl; return; } @@ -247,7 +247,7 @@ namespace VirtualRobot if (nPosX < 0 || nPosY < 0 || nPosX >= gridSizeX || nPosY >= gridSizeY) { - //cout << __PRETTY_FUNCTION__ << " internal error: " << fX << "," << fY << endl; + //cout << __PRETTY_FUNCTION__ << " internal error: " << fX << "," << fY << std::endl; return; } @@ -511,14 +511,14 @@ namespace VirtualRobot float totalMinY = std::numeric_limits<float>::max(); for(auto& grid : grids) { -// VR_INFO << "min: " << grid->getMin() << " max: " << grid->getMax() << endl; +// VR_INFO << "min: " << grid->getMin() << " max: " << grid->getMax() << std::endl; totalMinX = std::min(grid->getMin()(0), totalMinX); totalMinY = std::min(grid->getMin()(1), totalMinY); totalMaxX = std::max(grid->getMax()(0), totalMaxX); totalMaxY = std::max(grid->getMax()(1), totalMaxY); } WorkspaceGridPtr resultGrid(new WorkspaceGrid(totalMinX, totalMaxX, totalMinY, totalMaxY, grids.at(0)->getDiscretizeSize())); -// VR_INFO << "minx : " << totalMinX << " maxX: " << totalMaxX << " step size: " << resultGrid->getDiscretizeSize() << endl; +// VR_INFO << "minx : " << totalMinX << " maxX: " << totalMaxX << " step size: " << resultGrid->getDiscretizeSize() << std::endl; // int sameValueCount = 0; // int totalValueCount = 0; for(float x = totalMinX; x < totalMaxX; x += resultGrid->getDiscretizeSize()) @@ -541,7 +541,7 @@ namespace VirtualRobot resultGrid->setEntry(x, y, min, grasp); } } -// VR_INFO << "Same value percentage: " << (100.f * sameValueCount/totalValueCount) << endl; +// VR_INFO << "Same value percentage: " << (100.f * sameValueCount/totalValueCount) << std::endl; return resultGrid; } diff --git a/VirtualRobot/Workspace/WorkspaceRepresentation.cpp b/VirtualRobot/Workspace/WorkspaceRepresentation.cpp index 02b11124c2491157c1109e99775252598314a9b6..99b39eb57f616368dad0b847b92b4286a5b989ee 100644 --- a/VirtualRobot/Workspace/WorkspaceRepresentation.cpp +++ b/VirtualRobot/Workspace/WorkspaceRepresentation.cpp @@ -114,12 +114,12 @@ namespace VirtualRobot } catch(const std::exception &e) { - VR_ERROR << "Error:" << e.what() << endl << "Could not assign " << size << " bytes of memory. Reduce size of WorkspaceRepresentation data..." << endl; + VR_ERROR << "Error:" << e.what() << endl << "Could not assign " << size << " bytes of memory. Reduce size of WorkspaceRepresentation data..." << std::endl; throw; } catch (...) { - VR_ERROR << "Could not assign " << size << " bytes of memory. Reduce size of WorkspaceRepresentation data..." << endl; + VR_ERROR << "Could not assign " << size << " bytes of memory. Reduce size of WorkspaceRepresentation data..." << std::endl; throw; } @@ -208,7 +208,7 @@ namespace VirtualRobot // first check if the current version is used if (version[0] != versionMajor || version[1] != versionMinor) { - cout << "File version: " << version[0] << "." << version[1] << endl; + std::cout << "File version: " << version[0] << "." << version[1] << std::endl; // now check if an older version is used THROW_VR_EXCEPTION_IF( (version[0] > 2) || @@ -278,7 +278,7 @@ namespace VirtualRobot FileIO::readString(tmpString, file); if (tmpString.empty() || !robot->hasRobotNode(tmpString)) { - VR_WARNING << "Base ndoe not gifven/known:" << tmpString << endl; + VR_WARNING << "Base ndoe not gifven/known:" << tmpString << std::endl; } else { @@ -336,7 +336,7 @@ namespace VirtualRobot { if (!customLoad(file)) { - VR_ERROR << "Custom loading failed?!" << endl; + VR_ERROR << "Custom loading failed?!" << std::endl; } } @@ -430,7 +430,7 @@ namespace VirtualRobot if (!readOK || (n != dataSize && n != 0)) { - VR_ERROR << "Invalid number of bytes?!" << endl; + VR_ERROR << "Invalid number of bytes?!" << std::endl; bzip2->close(); file.close(); return; @@ -494,7 +494,7 @@ namespace VirtualRobot } catch (VirtualRobotException& e) { - VR_ERROR << e.what() << endl; + VR_ERROR << e.what() << std::endl; file.close(); throw; } @@ -602,7 +602,7 @@ namespace VirtualRobot if (!customSave(file)) { - VR_ERROR << "Custom saving failed?!" << endl; + VR_ERROR << "Custom saving failed?!" << std::endl; } // Data @@ -610,7 +610,7 @@ namespace VirtualRobot if (!data->save(file)) { - VR_ERROR << "Unable to store data!" << endl; + VR_ERROR << "Unable to store data!" << std::endl; return; } @@ -618,7 +618,7 @@ namespace VirtualRobot } catch (VirtualRobotException& e) { - cout << "exception: " << e.what() << endl; + std::cout << "exception: " << e.what() << std::endl; file.close(); throw; } @@ -970,134 +970,134 @@ namespace VirtualRobot void WorkspaceRepresentation::print() { - cout << "-----------------------------------------------------------" << endl; - cout << type << " - Status:" << endl; + std::cout << "-----------------------------------------------------------" << std::endl; + std::cout << type << " - Status:" << std::endl; if (data) { if (nodeSet) { - cout << "Kinematic Chain / RobotNodeSet: " << nodeSet->getName() << endl; + std::cout << "Kinematic Chain / RobotNodeSet: " << nodeSet->getName() << std::endl; } - cout << "Base Joint: "; + std::cout << "Base Joint: "; if (baseNode) { - cout << baseNode->getName() << endl; + std::cout << baseNode->getName() << std::endl; } else { - cout << "<GLOBAL POSE>" << endl; + std::cout << "<GLOBAL POSE>" << std::endl; } - cout << "TCP Joint: "; + std::cout << "TCP Joint: "; if (tcpNode) { - cout << tcpNode->getName() << endl; + std::cout << tcpNode->getName() << std::endl; } else { - cout << "<not set>" << endl; + std::cout << "<not set>" << std::endl; } - cout << "Orientation representation: "; + std::cout << "Orientation representation: "; switch (orientationType) { case RPY: - cout << "RPY" << endl; + std::cout << "RPY" << std::endl; break; case EulerXYZ: - cout << "EulerXYZ-Intrinsic" << endl; + std::cout << "EulerXYZ-Intrinsic" << std::endl; break; case EulerXYZExtrinsic: - cout << "EulerXYZ-Extrinsic" << endl; + std::cout << "EulerXYZ-Extrinsic" << std::endl; break; case Hopf: - cout << "Hopf" << endl; + std::cout << "Hopf" << std::endl; break; default: - cout << "NYI" << endl; + std::cout << "NYI" << std::endl; } - cout << "CollisionModel static: "; + std::cout << "CollisionModel static: "; if (staticCollisionModel) { - cout << staticCollisionModel->getName() << endl; + std::cout << staticCollisionModel->getName() << std::endl; } else { - cout << "<not set>" << endl; + std::cout << "<not set>" << std::endl; } - cout << "CollisionModel dynamic: "; + std::cout << "CollisionModel dynamic: "; if (dynamicCollisionModel) { - cout << dynamicCollisionModel->getName() << endl; + std::cout << dynamicCollisionModel->getName() << std::endl; } else { - cout << "<not set>" << endl; + std::cout << "<not set>" << std::endl; } - cout << "Used " << buildUpLoops << " loops for building the random configs " << endl; - cout << "Discretization step sizes: Translation: " << discretizeStepTranslation << " - Rotation: " << discretizeStepRotation << endl; - cout << type << " data extends: " << numVoxels[0] << "x" << numVoxels[1] << "x" << numVoxels[2] << "x" << numVoxels[3] << "x" << numVoxels[4] << "x" << numVoxels[5] << endl; + std::cout << "Used " << buildUpLoops << " loops for building the random configs " << std::endl; + std::cout << "Discretization step sizes: Translation: " << discretizeStepTranslation << " - Rotation: " << discretizeStepRotation << std::endl; + std::cout << type << " data extends: " << numVoxels[0] << "x" << numVoxels[1] << "x" << numVoxels[2] << "x" << numVoxels[3] << "x" << numVoxels[4] << "x" << numVoxels[5] << std::endl; long long nv = (long long)numVoxels[0] * (long long)numVoxels[1] * (long long)numVoxels[2] * (long long)numVoxels[3] * (long long)numVoxels[4] * (long long)numVoxels[5]; - cout << "Filled " << data->getVoxelFilledCount() << " of " << nv << " voxels" << endl; - cout << "Collisions: " << collisionConfigs << endl; - cout << "Maximum entry in a voxel: " << (int)data->getMaxEntry() << endl; - cout << type << " workspace extend (as defined on construction):" << endl; - cout << "Min boundary (local): "; + std::cout << "Filled " << data->getVoxelFilledCount() << " of " << nv << " voxels" << std::endl; + std::cout << "Collisions: " << collisionConfigs << std::endl; + std::cout << "Maximum entry in a voxel: " << (int)data->getMaxEntry() << std::endl; + std::cout << type << " workspace extend (as defined on construction):" << std::endl; + std::cout << "Min boundary (local): "; for (float minBound : minBounds) { - cout << minBound << ","; + std::cout << minBound << ","; } - cout << endl; - cout << "Max boundary (local): "; + std::cout << std::endl; + std::cout << "Max boundary (local): "; for (float maxBound : maxBounds) { - cout << maxBound << ","; + std::cout << maxBound << ","; } - cout << endl; - cout << "6D values achieved during buildup:" << endl; - cout << "Minimum 6D values: "; + std::cout << std::endl; + std::cout << "6D values achieved during buildup:" << std::endl; + std::cout << "Minimum 6D values: "; for (float achievedMinValue : achievedMinValues) { - cout << achievedMinValue << ","; + std::cout << achievedMinValue << ","; } - cout << endl; - cout << "Maximum 6D values: "; + std::cout << std::endl; + std::cout << "Maximum 6D values: "; for (float achievedMaxValue : achievedMaxValues) { - cout << achievedMaxValue << ","; + std::cout << achievedMaxValue << ","; } - cout << endl; + std::cout << std::endl; customPrint(); } else { - cout << type << " not created yet..." << endl; + std::cout << type << " not created yet..." << std::endl; } - cout << "-----------------------------------------------------------" << endl; - cout << endl; + std::cout << "-----------------------------------------------------------" << std::endl; + std::cout << std::endl; } void WorkspaceRepresentation::reset() @@ -1211,7 +1211,7 @@ namespace VirtualRobot { if (!data) { - VR_ERROR << "NULL DATA" << endl; + VR_ERROR << "NULL DATA" << std::endl; return 0; } @@ -1370,7 +1370,7 @@ namespace VirtualRobot i++; } - VR_ERROR << "Could not find a valid pose?!" << endl; + VR_ERROR << "Could not find a valid pose?!" << std::endl; return m; } @@ -1522,7 +1522,7 @@ namespace VirtualRobot { if (!robot || !nodeSet || !nodeSet->isKinematicChain()) { - VR_WARNING << "invalid data" << endl; + VR_WARNING << "invalid data" << std::endl; return false; } @@ -1533,13 +1533,13 @@ namespace VirtualRobot if (!robot->hasRobotNode(tcpNode)) { - VR_ERROR << "robot does not know tcp:" << tcpNode->getName() << endl; + VR_ERROR << "robot does not know tcp:" << tcpNode->getName() << std::endl; return false; } if (baseNode && !robot->hasRobotNode(baseNode)) { - VR_ERROR << "robot does not know baseNode:" << baseNode->getName() << endl; + VR_ERROR << "robot does not know baseNode:" << baseNode->getName() << std::endl; return false; } @@ -1884,21 +1884,21 @@ namespace VirtualRobot if (getVoxelFromPose(x, v)) { #if 0 - cout << "pose:"; + std::cout << "pose:"; for (int i = 0; i < 6; i++) { - cout << x[i] << ","; + std::cout << x[i] << ","; } - cout << "Voxel:"; + std::cout << "Voxel:"; for (int i = 0; i < 6; i++) { - cout << v[i] << ","; + std::cout << v[i] << ","; } - cout << endl; + std::cout << std::endl; #endif data->setDatumCheckNeighbors(v, e, neighborVoxels); } diff --git a/VirtualRobot/XML/BaseIO.cpp b/VirtualRobot/XML/BaseIO.cpp index 2c80d079a871b8d4fd311971b89ab0458670b468..92da80696ff66c26cb8ad0e5447c2b77c37989a7 100644 --- a/VirtualRobot/XML/BaseIO.cpp +++ b/VirtualRobot/XML/BaseIO.cpp @@ -123,7 +123,7 @@ namespace VirtualRobot if (!matrixXMLNode) { - VR_ERROR << "NULL matrix transform node?!" << endl; + VR_ERROR << "NULL matrix transform node?!" << std::endl; return m; } @@ -275,7 +275,7 @@ namespace VirtualRobot if (!hasUnitsAttribute(node)) { - VR_ERROR << "No units attribute at <" << tagName << ">" << endl; + VR_ERROR << "No units attribute at <" << tagName << ">" << std::endl; } Units u = getUnitsAttribute(node, Units::eAngle); @@ -342,7 +342,7 @@ namespace VirtualRobot } else { - VR_ERROR << "Ignoring unknown tag " << nodeName << endl; + VR_ERROR << "Ignoring unknown tag " << nodeName << std::endl; } node = node->next_sibling(); @@ -974,7 +974,7 @@ namespace VirtualRobot } else { - VR_WARNING << "No visualization present..." << endl; + VR_WARNING << "No visualization present..." << std::endl; } } else @@ -994,7 +994,7 @@ namespace VirtualRobot } else { - VR_WARNING << "VisualizationFactory of type '" << visuFileType << "' not present. Ignoring Visualization data in Robot Node <" << tagName << ">" << endl; + VR_WARNING << "VisualizationFactory of type '" << visuFileType << "' not present. Ignoring Visualization data in Robot Node <" << tagName << ">" << std::endl; } } else @@ -1010,7 +1010,7 @@ namespace VirtualRobot } else { - VR_WARNING << "VisualizationFactory of type '" << visuFileType << "' not present. Ignoring Visualization data in Robot Node <" << tagName << ">" << endl; + VR_WARNING << "VisualizationFactory of type '" << visuFileType << "' not present. Ignoring Visualization data in Robot Node <" << tagName << ">" << std::endl; } } @@ -1065,12 +1065,12 @@ namespace VirtualRobot } else if (auto factory = VisualizationFactory::fromName("inventor", NULL)) { - VR_WARNING << "VisualizationFactory of type '" << collisionFileType << "' not present. Trying factory for 'inventor' " << endl; + VR_WARNING << "VisualizationFactory of type '" << collisionFileType << "' not present. Trying factory for 'inventor' " << std::endl; visualizationNode = factory->createUnitedVisualization(visuNodes); } else { - VR_WARNING << "VisualizationFactory of type '" << collisionFileType << "' not present. Ignoring Visualization data in Robot Node <" << tagName << ">" << endl; + VR_WARNING << "VisualizationFactory of type '" << collisionFileType << "' not present. Ignoring Visualization data in Robot Node <" << tagName << ">" << std::endl; } } } @@ -1121,7 +1121,7 @@ namespace VirtualRobot } else { - VR_WARNING << "No visualization present..." << endl; + VR_WARNING << "No visualization present..." << std::endl; } } else @@ -1157,24 +1157,24 @@ namespace VirtualRobot } else { - VR_WARNING << "Ignoring data from " << visuFileXMLNode->value() << ": visualization type does not match to data from before." << endl; + VR_WARNING << "Ignoring data from " << visuFileXMLNode->value() << ": visualization type does not match to data from before." << std::endl; } } else if (auto factory = VisualizationFactory::fromName("inventor", NULL)) { - VR_WARNING << "VisualizationFactory of type '" << fileType << "' not present. Trying factory for 'inventor' " << endl; + VR_WARNING << "VisualizationFactory of type '" << fileType << "' not present. Trying factory for 'inventor' " << std::endl; if (tmpFileType == fileType) { result.push_back(factory->getVisualizationFromFile(visuFile, bbox)); } else { - VR_WARNING << "Ignoring data from " << visuFileXMLNode->value() << ": visualization type does not match to data from before." << endl; + VR_WARNING << "Ignoring data from " << visuFileXMLNode->value() << ": visualization type does not match to data from before." << std::endl; } } else { - VR_WARNING << "VisualizationFactory of type '" << fileType << "' not present. Ignoring Visualization data from " << visuFileXMLNode->value() << endl; + VR_WARNING << "VisualizationFactory of type '" << fileType << "' not present. Ignoring Visualization data from " << visuFileXMLNode->value() << std::endl; } } @@ -1280,7 +1280,7 @@ namespace VirtualRobot if (!hasUnitsAttribute(massXMLNode)) { - VR_ERROR << "No units attribute at <" << nodeName << ">" << endl; + VR_ERROR << "No units attribute at <" << nodeName << ">" << std::endl; } Units unit = getUnitsAttribute(massXMLNode, Units::eWeight); @@ -1298,7 +1298,7 @@ namespace VirtualRobot } else { - VR_WARNING << "Expecting mass tag for physics node in <" << nodeName << ">." << endl; + VR_WARNING << "Expecting mass tag for physics node in <" << nodeName << ">." << std::endl; physics.massKg = 0.0f; } @@ -1514,7 +1514,7 @@ namespace VirtualRobot return absFileName; } - VR_ERROR << "Could not determine valid filename from " << fileName << endl; + VR_ERROR << "Could not determine valid filename from " << fileName << std::endl; } return fileName; @@ -1541,7 +1541,7 @@ namespace VirtualRobot if (!hasUnitsAttribute(node)) { - VR_ERROR << "No units attribute at <" << storeConfigName << ">" << endl; + VR_ERROR << "No units attribute at <" << storeConfigName << ">" << std::endl; } /*if (getUnitsAttribute(node, Units::eAngle).isDegree()) @@ -1640,7 +1640,7 @@ namespace VirtualRobot ss << robo->getType() << "_RobotNodeSet_" << robotNodeSetCounter; nodeSetName = ss.str(); robotNodeSetCounter++; - VR_WARNING << "RobotNodeSet definition expects attribute 'name'. Setting name to " << nodeSetName << endl; + VR_WARNING << "RobotNodeSet definition expects attribute 'name'. Setting name to " << nodeSetName << std::endl; } if (rootNodeName.empty()) @@ -1749,7 +1749,7 @@ namespace VirtualRobot if (trajName.empty()) { trajName = "Trajectory"; - VR_WARNING << "Trajectory definition expects attribute 'RobotNodeSet'. Setting to " << trajName << endl; + VR_WARNING << "Trajectory definition expects attribute 'RobotNodeSet'. Setting to " << trajName << std::endl; } RobotPtr r; @@ -1770,7 +1770,7 @@ namespace VirtualRobot assert(dim >= 0); if (static_cast<unsigned int>(dim) != rns->getSize()) { - VR_WARNING << " Invalid dim attribute (" << dim << "). Setting dimension to " << rns->getSize() << endl; + VR_WARNING << " Invalid dim attribute (" << dim << "). Setting dimension to " << rns->getSize() << std::endl; dim = rns->getSize(); } @@ -1787,7 +1787,7 @@ namespace VirtualRobot if (!processFloatValueTags(node, dim, p)) { - VR_ERROR << "Error in processing configuration. Skipping entry" << endl; + VR_ERROR << "Error in processing configuration. Skipping entry" << std::endl; } else { @@ -1833,7 +1833,7 @@ namespace VirtualRobot std::string BaseIO::toXML(const Eigen::Matrix4f& m, std::string ident /*= "\t"*/) { std::stringstream ss; - ss << ident << "<Matrix4x4 units='mm'>" << endl; + ss << ident << "<Matrix4x4 units='mm'>" << std::endl; for (int r = 1; r <= 4; r++) { @@ -1844,10 +1844,10 @@ namespace VirtualRobot ss << "c" << i << "='" << m(r - 1, i - 1) << "' "; } - ss << "/>" << endl; + ss << "/>" << std::endl; } - ss << ident << "</Matrix4x4>" << endl; + ss << ident << "</Matrix4x4>" << std::endl; return ss.str(); } diff --git a/VirtualRobot/XML/ObjectIO.cpp b/VirtualRobot/XML/ObjectIO.cpp index 40670a0cb9bb8cb94eb2d6e4a8c1022e553f4c8c..7a2c973c56af5d10218dc62bb0efbe12a57838fa 100644 --- a/VirtualRobot/XML/ObjectIO.cpp +++ b/VirtualRobot/XML/ObjectIO.cpp @@ -148,7 +148,7 @@ namespace VirtualRobot { if (!t || t->faces.size() == 0) { - VR_ERROR << "Wrong input" << endl; + VR_ERROR << "Wrong input" << std::endl; return false; } @@ -156,11 +156,11 @@ namespace VirtualRobot of.open(filename.c_str()); if (!of) { - VR_ERROR << "Could not open " << filename << " for writing" << endl; + VR_ERROR << "Could not open " << filename << " for writing" << std::endl; return false; } - of << "solid " << objectName << endl; + of << "solid " << objectName << std::endl; // write triangles for (size_t i = 0; i < t->faces.size(); i++) @@ -181,16 +181,16 @@ namespace VirtualRobot // compute normal //Vector n = CGAL::cross_product( q-p, r-p); //Vector norm = n / std::sqrt( n * n); - of << " facet normal " << n(0) << " " << n(1) << " " << n(2) << endl; - of << " outer loop " << endl; - of << " vertex " << p1(0)*scaling << " " << p1(1)*scaling << " " << p1(2)*scaling << endl; - of << " vertex " << p2(0)*scaling << " " << p2(1)*scaling << " " << p2(2)*scaling << endl; - of << " vertex " << p3(0)*scaling << " " << p3(1)*scaling << " " << p3(2)*scaling << endl; - of << " endloop " << endl; - of << " endfacet " << endl; + of << " facet normal " << n(0) << " " << n(1) << " " << n(2) << std::endl; + of << " outer loop " << std::endl; + of << " vertex " << p1(0)*scaling << " " << p1(1)*scaling << " " << p1(2)*scaling << std::endl; + of << " vertex " << p2(0)*scaling << " " << p2(1)*scaling << " " << p2(2)*scaling << std::endl; + of << " vertex " << p3(0)*scaling << " " << p3(1)*scaling << " " << p3(2)*scaling << std::endl; + of << " endloop " << std::endl; + of << " endfacet " << std::endl; } - of << "endsolid " << objectName << endl; + of << "endsolid " << objectName << std::endl; of.close(); return true; } diff --git a/VirtualRobot/XML/RobotIO.cpp b/VirtualRobot/XML/RobotIO.cpp index ffd601195f654e083fbd5ad341829e9719b8c2fb..f7eee3c1abca5b346ced7b8b16f48ac0bb69cf27 100644 --- a/VirtualRobot/XML/RobotIO.cpp +++ b/VirtualRobot/XML/RobotIO.cpp @@ -106,13 +106,13 @@ namespace VirtualRobot { if (unit.isLength()) { - VR_WARNING << "No 'lo' attribute in <Limits> tag. Assuming -1000 [mm]." << endl; + VR_WARNING << "No 'lo' attribute in <Limits> tag. Assuming -1000 [mm]." << std::endl; jointLimitLo = -1000.0f; unit = Units("mm"); } else { - VR_WARNING << "No 'lo' attribute in <Limits> tag. Assuming -180 [deg]." << endl; + VR_WARNING << "No 'lo' attribute in <Limits> tag. Assuming -180 [deg]." << std::endl; jointLimitLo = float(-M_PI); unit = Units("rad"); } @@ -126,13 +126,13 @@ namespace VirtualRobot { if (unit.isLength()) { - VR_WARNING << "No 'hi' attribute in <Limits> tag. Assuming 1000 [mm]." << endl; + VR_WARNING << "No 'hi' attribute in <Limits> tag. Assuming 1000 [mm]." << std::endl; jointLimitLo = 1000.0f; unit = Units("mm"); } else { - VR_WARNING << "No 'hi' attribute in <Limits> tag. Assuming 180 [deg]." << endl; + VR_WARNING << "No 'hi' attribute in <Limits> tag. Assuming 180 [deg]." << std::endl; jointLimitHi = float(M_PI); unit = Units("rad"); } @@ -161,7 +161,7 @@ namespace VirtualRobot if (limitless && unit.isAngle() && (unit.toDegree(jointLimitHi) - unit.toDegree(jointLimitLo) != 360)) { VR_WARNING << "Limitless Joint: Angular distance between 'lo' and 'hi' attributes should equal 2*pi [rad] or 360 [deg]." << endl - << "Setting 'lo' to -pi and 'hi' to pi [rad]..." << endl; + << "Setting 'lo' to -pi and 'hi' to pi [rad]..." << std::endl; jointLimitLo = float(-M_PI); jointLimitHi = float(M_PI); } @@ -173,7 +173,7 @@ namespace VirtualRobot { if (!rn || !sensorXMLNode) { - VR_ERROR << "NULL DATA ?!" << endl; + VR_ERROR << "NULL DATA ?!" << std::endl; return false; } @@ -188,7 +188,7 @@ namespace VirtualRobot } else { - VR_WARNING << "No 'type' attribute for <Sensor> tag. Skipping Sensor definition of RobotNode " << rn->getName() << "!" << endl; + VR_WARNING << "No 'type' attribute for <Sensor> tag. Skipping Sensor definition of RobotNode " << rn->getName() << "!" << std::endl; return false; } @@ -203,7 +203,7 @@ namespace VirtualRobot } else { - VR_WARNING << "No Factory found for sensor of type " << sensorType << ". Skipping Sensor definition of RobotNode " << rn->getName() << "!" << endl; + VR_WARNING << "No Factory found for sensor of type " << sensorType << ". Skipping Sensor definition of RobotNode " << rn->getName() << "!" << std::endl; return false; } @@ -258,7 +258,7 @@ namespace VirtualRobot } else { - VR_WARNING << "No 'type' attribute for <Joint> tag. Assuming fixed joint for RobotNode " << robotNodeName << "!" << endl; + VR_WARNING << "No 'type' attribute for <Joint> tag. Assuming fixed joint for RobotNode " << robotNodeName << "!" << std::endl; jointType = RobotNodeFixedFactory::getName(); } @@ -506,7 +506,7 @@ namespace VirtualRobot { if (scaleVisu) { - VR_WARNING << "Ignoring ScaleVisualization in Revolute joint." << endl; + VR_WARNING << "Ignoring ScaleVisualization in Revolute joint." << std::endl; scaleVisu = false; } @@ -519,7 +519,7 @@ namespace VirtualRobot else { // silently setting axis to (0,0,1) - //VR_WARNING << "Joint '" << robotNodeName << "' without 'axis' tag. Setting rotation axis to (0,0,1)." << endl; + //VR_WARNING << "Joint '" << robotNodeName << "' without 'axis' tag. Setting rotation axis to (0,0,1)." << std::endl; axis << 0, 0, 1.0f; //THROW_VR_EXCEPTION("joint '" << robotNodeName << "' wrongly defined, expecting 'axis' tag." << endl); } @@ -626,7 +626,7 @@ namespace VirtualRobot ss << robo->getType() << "_Node_" << robotNodeCounter; robotNodeName = ss.str(); robotNodeCounter++; - VR_WARNING << "RobotNode definition expects attribute 'name'. Setting name to " << robotNodeName << endl; + VR_WARNING << "RobotNode definition expects attribute 'name'. Setting name to " << robotNodeName << std::endl; } @@ -797,7 +797,7 @@ namespace VirtualRobot } else { - VR_WARNING << "VisualizationFactory of type '" << visuFileType << "' not present. Ignoring Visualization data." << endl; + VR_WARNING << "VisualizationFactory of type '" << visuFileType << "' not present. Ignoring Visualization data." << std::endl; } } } @@ -835,7 +835,7 @@ namespace VirtualRobot std::filesystem::path filenameBasePath(basePath); std::filesystem::path filenameNewComplete = filenameBasePath / filenameNew; - VR_INFO << "Searching robot: " << filenameNewComplete.string() << endl; + VR_INFO << "Searching robot: " << filenameNewComplete.string() << std::endl; try { @@ -1150,7 +1150,7 @@ namespace VirtualRobot } else { - VR_WARNING << "Ignoring unknown attribute in EEF <" << endeffectorName << "> definition:" << attributeName << endl; + VR_WARNING << "Ignoring unknown attribute in EEF <" << endeffectorName << "> definition:" << attributeName << std::endl; } attr = attr->next_attribute(); @@ -1179,7 +1179,7 @@ namespace VirtualRobot } else { - VR_ERROR << "There should only be one <static> tag inside <endeffector> tags" << endl; + VR_ERROR << "There should only be one <static> tag inside <endeffector> tags" << std::endl; } } else if ("preshape" == nodeName) @@ -1430,7 +1430,7 @@ namespace VirtualRobot if (!RuntimeEnvironment::getDataFileAbsolute(fullFile)) { - VR_ERROR << "Could not open XML file:" << xmlFile << endl; + VR_ERROR << "Could not open XML file:" << xmlFile << std::endl; return RobotPtr(); } @@ -1439,7 +1439,7 @@ namespace VirtualRobot if (!in.is_open()) { - VR_ERROR << "Could not open XML file:" << fullFile << endl; + VR_ERROR << "Could not open XML file:" << fullFile << std::endl; return RobotPtr(); } @@ -1456,7 +1456,7 @@ namespace VirtualRobot if (!res) { - VR_ERROR << "Error while parsing file " << fullFile << endl; + VR_ERROR << "Error while parsing file " << fullFile << std::endl; } res->applyJointValues(); @@ -1478,7 +1478,7 @@ namespace VirtualRobot if (std::filesystem::exists(modelDirComplete) && !std::filesystem::is_directory(modelDirComplete)) { - VR_ERROR << "Could not create model directory (existing & !dir) " << pModelDir.string() << endl; + VR_ERROR << "Could not create model directory (existing & !dir) " << pModelDir.string() << std::endl; return false; } @@ -1486,7 +1486,7 @@ namespace VirtualRobot { if (!std::filesystem::create_directories(modelDirComplete)) { - VR_ERROR << "Could not create model dir " << modelDirComplete.string() << endl; + VR_ERROR << "Could not create model dir " << modelDirComplete.string() << std::endl; return false; } } @@ -1495,7 +1495,7 @@ namespace VirtualRobot if (!f) { - VR_ERROR << "Could not create file " << fnComplete.string() << endl; + VR_ERROR << "Could not create file " << fnComplete.string() << std::endl; return false; } diff --git a/VirtualRobot/XML/SceneIO.cpp b/VirtualRobot/XML/SceneIO.cpp index de765e77790bd05b3232e486904a3a7a934484ca..9f322ebfe3feebb783c447b587e2d6bfd8153f94 100644 --- a/VirtualRobot/XML/SceneIO.cpp +++ b/VirtualRobot/XML/SceneIO.cpp @@ -394,7 +394,7 @@ namespace VirtualRobot { if (!s) { - VR_ERROR << "NULL data..." << endl; + VR_ERROR << "NULL data..." << std::endl; return false; } diff --git a/VirtualRobot/examples/CameraViewer/CameraViewer.cpp b/VirtualRobot/examples/CameraViewer/CameraViewer.cpp index 3c782bb8f33f02ebb216e07ce555946c8c5d3f7c..7bcc608cb66f07bd654acb781369c6c29b25e151 100644 --- a/VirtualRobot/examples/CameraViewer/CameraViewer.cpp +++ b/VirtualRobot/examples/CameraViewer/CameraViewer.cpp @@ -38,7 +38,7 @@ int main(int argc, char* argv[]) VirtualRobot::RuntimeEnvironment::processCommandLine(argc, argv); VirtualRobot::RuntimeEnvironment::print(); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; std::string filename("robots/ArmarIII/ArmarIII.xml"); std::string cam1Name("EyeLeftCamera"); @@ -65,7 +65,7 @@ int main(int argc, char* argv[]) } - cout << "Using robot:" << filename << ", cam1:" << cam1Name << ", cam2:" << cam2Name << endl; + std::cout << "Using robot:" << filename << ", cam1:" << cam1Name << ", cam2:" << cam2Name << std::endl; showCamWindow rw(filename, cam1Name, cam2Name); diff --git a/VirtualRobot/examples/CameraViewer/showCamWindow.cpp b/VirtualRobot/examples/CameraViewer/showCamWindow.cpp index 7610b5d5a0a32cd56a28c9883906e4fe6c586f3d..4a411ac86b02c21f95cd99f4d930fc71e804e1cc 100644 --- a/VirtualRobot/examples/CameraViewer/showCamWindow.cpp +++ b/VirtualRobot/examples/CameraViewer/showCamWindow.cpp @@ -33,7 +33,7 @@ float TIMER_MS = 30.0f; showCamWindow::showCamWindow(std::string& sRobotFilename, std::string& cam1Name, std::string& cam2Name) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; //this->setCaption(QString("ShowRobot - KIT - Humanoids Group")); //resize(1100, 768); cam2Renderer = nullptr; @@ -284,7 +284,7 @@ void showCamWindow::updateRNSBox() void showCamWindow::selectRNS(int nr) { currentRobotNodeSet.reset(); - cout << "Selecting RNS nr " << nr << endl; + std::cout << "Selecting RNS nr " << nr << std::endl; if (nr <= 0) { @@ -302,7 +302,7 @@ void showCamWindow::selectRNS(int nr) currentRobotNodeSet = robotNodeSets[nr]; currentRobotNodes = currentRobotNodeSet->getAllRobotNodes(); - /*cout << "HIGHLIGHTING rns " << currentRobotNodeSet->getName() << endl; + /*cout << "HIGHLIGHTING rns " << currentRobotNodeSet->getName() << std::endl; if (visualization) { @@ -324,7 +324,7 @@ void showCamWindow::selectJoint(int nr) } currentRobotNode.reset(); - cout << "Selecting Joint nr " << nr << endl; + std::cout << "Selecting Joint nr " << nr << std::endl; if (nr < 0 || nr >= (int)currentRobotNodes.size()) { @@ -355,7 +355,7 @@ void showCamWindow::selectJoint(int nr) UI.horizontalSliderPos->setEnabled(false); } - cout << "HIGHLIGHTING node " << currentRobotNodes[nr]->getName() << endl; + std::cout << "HIGHLIGHTING node " << currentRobotNodes[nr]->getName() << std::endl; if (visualization) { @@ -399,7 +399,7 @@ void showCamWindow::selectRobot() void showCamWindow::loadRobot() { robotSep->removeAllChildren(); - cout << "Loading Robot from " << m_sRobotFilename << endl; + std::cout << "Loading Robot from " << m_sRobotFilename << std::endl; currentRobotNode.reset(); currentRobotNodes.clear(); currentRobotNodeSet.reset(); @@ -413,7 +413,7 @@ void showCamWindow::loadRobot() if (!importer) { - cout << " ERROR while grabbing importer" << endl; + std::cout << " ERROR while grabbing importer" << std::endl; return; } @@ -423,14 +423,14 @@ void showCamWindow::loadRobot() } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return; } diff --git a/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp b/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp index ab8e664f0042bcc0c73a4a8d9b94acfcd1a605e2..5b87967c2ac16c463097db4eb30fef49f49931c5 100644 --- a/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp +++ b/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp @@ -261,7 +261,7 @@ void ConstrainedIKWindow::computeTSRError() void ConstrainedIKWindow::selectKC(int nr) { - cout << "Selecting kinematic chain nr " << nr << endl; + std::cout << "Selecting kinematic chain nr " << nr << std::endl; if (nr < 0 || nr >= (int)kinChains.size()) { @@ -370,10 +370,10 @@ void ConstrainedIKWindow::solve() std::vector<RobotNodePtr> nodes = kc->getAllRobotNodes(); - std::cout << "Joint values: " << endl; + std::cout << "Joint values: " << std::endl; for (auto &node : nodes) { - std::cout << node->getName() << ": " << node->getJointValue() << endl; + std::cout << node->getName() << ": " << node->getJointValue() << std::endl; } if(UI.poseGroup->isChecked()) @@ -674,7 +674,7 @@ void ConstrainedIKWindow::loadRobot() { std::cout << "ConstrainedIKWindow: Loading robot" << std::endl; robotSep->removeAllChildren(); - cout << "Loading Robot from " << robotFilename << endl; + std::cout << "Loading Robot from " << robotFilename << std::endl; try { @@ -682,14 +682,14 @@ void ConstrainedIKWindow::loadRobot() } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return; } diff --git a/VirtualRobot/examples/GenericIK/GenericIKDemo.cpp b/VirtualRobot/examples/GenericIK/GenericIKDemo.cpp index 54a20e3bf48081ef14920631aec008b4631a72a6..54beb0f03651287f425981f52d5ef5d093dbc455 100644 --- a/VirtualRobot/examples/GenericIK/GenericIKDemo.cpp +++ b/VirtualRobot/examples/GenericIK/GenericIKDemo.cpp @@ -29,7 +29,7 @@ bool useColModel = false; int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "Generic IK Demo"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; VirtualRobot::RuntimeEnvironment::considerKey("robot"); @@ -50,7 +50,7 @@ int main(int argc, char* argv[]) } } - cout << "Using robot at " << filename << endl; + std::cout << "Using robot at " << filename << std::endl; GenericIKWindow rw(filename); diff --git a/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp b/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp index 31df44ea6bb5b596bb8d0997fe6dd596486d006a..cde207f5845a1e9c0150c1d7e07bc7a30c729c51 100644 --- a/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp +++ b/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp @@ -21,7 +21,7 @@ float TIMER_MS = 30.0f; GenericIKWindow::GenericIKWindow(std::string& sRobotFilename) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; //this->setCaption(QString("ShowRobot - KIT - Humanoids Group")); //resize(1100, 768); @@ -258,7 +258,7 @@ void GenericIKWindow::updateKCBox() void GenericIKWindow::selectKC(int nr) { - cout << "Selecting kinematic chain nr " << nr << endl; + std::cout << "Selecting kinematic chain nr " << nr << std::endl; if (nr < 0 || nr >= (int)kinChains.size()) { @@ -351,7 +351,7 @@ void GenericIKWindow::solve() return; } - cout << "---- Solve IK ----" << endl; + std::cout << "---- Solve IK ----" << std::endl; IKSolver::CartesianSelection s = IKSolver::All; @@ -370,7 +370,7 @@ void GenericIKWindow::solve() { // setup gaze IK float v = (kc->getNode(kc->getSize() - 1)->getParent()->getGlobalPose().block(0, 3, 3, 1) - targetPose.block(0, 3, 3, 1)).norm(); - cout << "Setting initial value of translation joint to :" << v << endl; + std::cout << "Setting initial value of translation joint to :" << v << std::endl; ikSolver->setupTranslationalJoint(kc->getNode(kc->getSize() - 1), v); kc->getNode(kc->getSize() - 1)->setJointValue(v); }*/ @@ -378,18 +378,18 @@ void GenericIKWindow::solve() if (UI.comboBoxIKMethod->currentIndex() == 0) { - cout << "Solving with Gaze IK" << endl; + std::cout << "Solving with Gaze IK" << std::endl; ikGazeSolver->solve(targetPose.block(0, 3, 3, 1)); } else if(UI.comboBoxIKMethod->currentIndex() == 1) { - cout << "Solving with Differential IK" << endl; + std::cout << "Solving with Differential IK" << std::endl; ikSolver->solve(targetPose, s, 50); } else { #ifdef USE_NLOPT - cout << "Solving with Constrained IK" << endl; + std::cout << "Solving with Constrained IK" << std::endl; ConstrainedOptimizationIK solver(robot, kc); PoseConstraintPtr pc(new PoseConstraint(robot, kc, tcp, targetPose, s)); @@ -398,7 +398,7 @@ void GenericIKWindow::solve() solver.initialize(); solver.solve(); #else - cout << "Constrained IK not available (requires NLopt)" << endl; + std::cout << "Constrained IK not available (requires NLopt)" << std::endl; #endif } @@ -425,12 +425,12 @@ void GenericIKWindow::solve() qd3 += " deg"; UI.labelOri->setText(qd3); - cout << "Joint values:" << endl; + std::cout << "Joint values:" << std::endl; std::vector<RobotNodePtr> nodes = kc->getAllRobotNodes(); for (auto & node : nodes) { - cout << node->getJointValue() << endl; + std::cout << node->getJointValue() << std::endl; } /* @@ -440,7 +440,7 @@ void GenericIKWindow::solve() */ exViewer->render(); - cout << "---- END Solve IK ----" << endl; + std::cout << "---- END Solve IK ----" << std::endl; } void GenericIKWindow::box2TCP() @@ -464,7 +464,7 @@ void GenericIKWindow::loadRobot() { std::cout << "GenericIKWindow: Loading robot" << std::endl; robotSep->removeAllChildren(); - cout << "Loading Robot from " << robotFilename << endl; + std::cout << "Loading Robot from " << robotFilename << std::endl; try { @@ -472,14 +472,14 @@ void GenericIKWindow::loadRobot() } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return; } diff --git a/VirtualRobot/examples/GraspEditor/GraspEditor.cpp b/VirtualRobot/examples/GraspEditor/GraspEditor.cpp index a4fb77902d66e841d35be6d50158138ce905c6c8..780e59ae0e140c80a1dc61281a0e3dffd70aff95 100644 --- a/VirtualRobot/examples/GraspEditor/GraspEditor.cpp +++ b/VirtualRobot/examples/GraspEditor/GraspEditor.cpp @@ -27,7 +27,7 @@ using namespace VirtualRobot; int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "GraspEditor"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; std::string filename1("objects/plate.xml"); std::string filename2("robots/ArmarIII/ArmarIII.xml"); diff --git a/VirtualRobot/examples/InverseDynamics/InverseDynamics.cpp b/VirtualRobot/examples/InverseDynamics/InverseDynamics.cpp index 6e052588a50089f14393a791c26af246b4e66a95..0d95096560823c373f7c1aed615a6e0eb47c4e9b 100644 --- a/VirtualRobot/examples/InverseDynamics/InverseDynamics.cpp +++ b/VirtualRobot/examples/InverseDynamics/InverseDynamics.cpp @@ -17,7 +17,7 @@ int main(int argc, char* argv[]) std::string filename("robots/ArmarIII/ArmarIII.xml"); VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(filename); VirtualRobot::RuntimeEnvironment::processCommandLine(argc, argv); - cout << "Using robot at " << filename << std::endl; + std::cout << "Using robot at " << filename << std::endl; RobotPtr rob; try @@ -26,7 +26,7 @@ int main(int argc, char* argv[]) } catch (VirtualRobotException& e) { - cout << "Error: " << e.what() << std::endl; + std::cout << "Error: " << e.what() << std::endl; return -1; } @@ -97,7 +97,7 @@ int main(int argc, char* argv[]) std::vector<float> gravityVR; g.computeGravityTorque(gravityVR); -// cout << "joint torques from inverse dynamics: " << endl << invDyn << endl; +// std::cout << "joint torques from inverse dynamics: " << endl << invDyn << std::endl; std::cout << "joint space inertia matrix: " << std::endl << dynamics.getInertiaMatrix(q) << std::endl; std::cout << "joint space gravitational matrix:" << std::endl << dynamics.getGravityMatrix(q) << std::endl; std::cout << "joint space VR gravity :" << std::endl; @@ -109,7 +109,7 @@ int main(int argc, char* argv[]) } std::cout << "joint space coriolis matrix:" << std::endl << dynamics.getCoriolisMatrix(q, qdot) << std::endl; std::cout << "joint space accelerations from forward dynamics:" << std::endl << dynamics.getForwardDynamics(q, qdot, tau) << std::endl; -// cout << "Identifier for Elbow R:" << endl << dynamics.getIdentifier("Elbow R") << endl; +// std::cout << "Identifier for Elbow R:" << endl << dynamics.getIdentifier("Elbow R") << std::endl; } else diff --git a/VirtualRobot/examples/Jacobi/JacobiDemo.cpp b/VirtualRobot/examples/Jacobi/JacobiDemo.cpp index ece3f03c35a1f6bf2a8836d6a1613faa562b38f6..bbfa7075d7fda2fd8a6a93c036d50ef86df547d5 100644 --- a/VirtualRobot/examples/Jacobi/JacobiDemo.cpp +++ b/VirtualRobot/examples/Jacobi/JacobiDemo.cpp @@ -30,7 +30,7 @@ int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "Jacobi Demo"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; std::string filename("robots/ArmarIII/ArmarIII.xml"); VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(filename); JacobiWindow rw(filename); diff --git a/VirtualRobot/examples/Jacobi/JacobiWindow.cpp b/VirtualRobot/examples/Jacobi/JacobiWindow.cpp index 0b60a2ad6980b567e8e414bda194b7b444e32ba6..4bdf1f8b54331f6abc836161583c5ed3362c6570 100644 --- a/VirtualRobot/examples/Jacobi/JacobiWindow.cpp +++ b/VirtualRobot/examples/Jacobi/JacobiWindow.cpp @@ -17,7 +17,7 @@ float TIMER_MS = 30.0f; JacobiWindow::JacobiWindow(std::string& sRobotFilename) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; //this->setCaption(QString("ShowRobot - KIT - Humanoids Group")); //resize(1100, 768); @@ -342,7 +342,7 @@ void JacobiWindow::updateKCBox() void JacobiWindow::selectKC(int nr) { - cout << "Selecting kinematic chain nr " << nr << endl; + std::cout << "Selecting kinematic chain nr " << nr << std::endl; if (nr < 0 || nr >= (int)kinChains.size()) { @@ -438,7 +438,7 @@ void JacobiWindow::jacobiTest() return; } - cout << "---- TEST JACOBI ----" << endl; + std::cout << "---- TEST JACOBI ----" << std::endl; DifferentialIKPtr j(new DifferentialIK(kc)); Eigen::Matrix4f targetPose = box->getGlobalPose(); @@ -447,7 +447,7 @@ void JacobiWindow::jacobiTest() j->computeSteps(0.2f, 0, 50); exViewer->render(); - cout << "---- END TEST JACOBI ----" << endl; + std::cout << "---- END TEST JACOBI ----" << std::endl; } void JacobiWindow::jacobiTest2() @@ -457,7 +457,7 @@ void JacobiWindow::jacobiTest2() return; } - cout << "---- TEST JACOBI ----" << endl; + std::cout << "---- TEST JACOBI ----" << std::endl; //std::vector<RobotNodePtr> n; //n.push_back(tcp); //n.push_back(elbow); @@ -472,7 +472,7 @@ void JacobiWindow::jacobiTest2() j->computeSteps(0.2f, 0, 40); exViewer->render(); - cout << "---- END TEST JACOBI ----" << endl; + std::cout << "---- END TEST JACOBI ----" << std::endl; } void JacobiWindow::jacobiTestBi() @@ -482,7 +482,7 @@ void JacobiWindow::jacobiTestBi() return; } - cout << "---- TEST JACOBI ----" << endl; + std::cout << "---- TEST JACOBI ----" << std::endl; //std::vector<RobotNodePtr> n; //n.push_back(tcp); //n.push_back(tcp2); @@ -517,7 +517,7 @@ void JacobiWindow::jacobiTestBi() j->computeSteps(0.2f, 0, 50); exViewer->render(); - cout << "---- END TEST JACOBI ----" << endl; + std::cout << "---- END TEST JACOBI ----" << std::endl; } void JacobiWindow::box2TCP() @@ -548,14 +548,14 @@ void JacobiWindow::box2TCP() void JacobiWindow::sliderPressed() { - cout << "GG "; + std::cout << "GG "; } void JacobiWindow::loadRobot() { std::cout << "JacobiWindow: Loading robot" << std::endl; robotSep->removeAllChildren(); - cout << "Loading Robot from " << robotFilename << endl; + std::cout << "Loading Robot from " << robotFilename << std::endl; try { @@ -563,14 +563,14 @@ void JacobiWindow::loadRobot() } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return; } diff --git a/VirtualRobot/examples/ReachabilityMap/ReachabilityMapScene.cpp b/VirtualRobot/examples/ReachabilityMap/ReachabilityMapScene.cpp index 94f0cb32b8d538a85cf5c1b4a3a3a0af3c59539d..cbb14c9aa5ca3ad1aecd1d7edd681417bf31507b 100644 --- a/VirtualRobot/examples/ReachabilityMap/ReachabilityMapScene.cpp +++ b/VirtualRobot/examples/ReachabilityMap/ReachabilityMapScene.cpp @@ -27,7 +27,7 @@ int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "Reachability Map Demo"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; std::string filenameReach; std::string eef; @@ -50,7 +50,7 @@ int main(int argc, char* argv[]) VirtualRobot::RuntimeEnvironment::processCommandLine(argc, argv); VirtualRobot::RuntimeEnvironment::print(); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; if (VirtualRobot::RuntimeEnvironment::hasValue("robot")) { @@ -87,10 +87,10 @@ int main(int argc, char* argv[]) eef = VirtualRobot::RuntimeEnvironment::getValue("eef"); } - cout << "Using robot at " << filenameRob << endl; - cout << "Using eef " << eef << endl; - cout << "Using manipulation object at " << fileObj << endl; - cout << "Using reachability file from " << filenameReach << endl; + std::cout << "Using robot at " << filenameRob << std::endl; + std::cout << "Using eef " << eef << std::endl; + std::cout << "Using manipulation object at " << fileObj << std::endl; + std::cout << "Using reachability file from " << filenameReach << std::endl; ReachabilityMapWindow rw(filenameRob, filenameReach, fileObj, eef); diff --git a/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp b/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp index f507b950d891ab1a483f3fd6f24b391a50938bc6..99265fcd8552300d3dceecbe5be37081de1882b9 100644 --- a/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp +++ b/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp @@ -31,7 +31,7 @@ float TIMER_MS = 30.0f; ReachabilityMapWindow::ReachabilityMapWindow(std::string& sRobotFile, std::string& reachFile, std::string& objFile, std::string& eef) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; robotFile = sRobotFile; VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(robotFile); @@ -312,7 +312,7 @@ void ReachabilityMapWindow::buildReachVisu() WorkspaceRepresentation::WorkspaceCut2DPtr cutData = reachSpace->createCut(pose,reachSpace->getDiscretizeParameterTranslation(), false); int maxCoeff = cutData->entries.maxCoeff(); - VR_INFO << "Max coeff:" << maxCoeff << endl; + VR_INFO << "Max coeff:" << maxCoeff << std::endl; SoNode *visualisationNode = CoinVisualizationFactory::getCoinVisualization(cutData, VirtualRobot::ColorMap(VirtualRobot::ColorMap::eHot), Eigen::Vector3f::UnitZ(), maxCoeff); @@ -536,7 +536,7 @@ void ReachabilityMapWindow::selectEEF(int nr) return; } - cout << "Selecting EEF nr " << nr << endl; + std::cout << "Selecting EEF nr " << nr << std::endl; std::vector<EndEffectorPtr> eefs = robot->getEndEffectors(); std::string tcp = "<not set>"; @@ -586,7 +586,7 @@ void ReachabilityMapWindow::selectEEF(std::string& eef) void ReachabilityMapWindow::loadRobot() { robotVisuSep->removeAllChildren(); - cout << "Loading robot from " << robotFile << endl; + std::cout << "Loading robot from " << robotFile << std::endl; try { @@ -594,14 +594,14 @@ void ReachabilityMapWindow::loadRobot() } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return; } @@ -653,7 +653,7 @@ void ReachabilityMapWindow::loadReachFile(std::string filename) } catch (...) { - VR_ERROR << "Coulkd not load reachability file..." << endl; + VR_ERROR << "Coulkd not load reachability file..." << std::endl; } } @@ -661,13 +661,13 @@ void ReachabilityMapWindow::loadReachFile(std::string filename) reachSpace->print(); /*if (reachSpace->getNodeSet()) { - cout << "Using RNS: " << reachSpace->getNodeSet()->getName() << endl; + std::cout << "Using RNS: " << reachSpace->getNodeSet()->getName() << std::endl; for (size_t i=0;i<robotNodeSets.size();i++) { - cout << "checking " << robotNodeSets[i]->getName() << endl; + std::cout << "checking " << robotNodeSets[i]->getName() << std::endl; if (robotNodeSets[i] == reachSpace->getNodeSet()) { - cout << "Found RNS.." << endl; + std::cout << "Found RNS.." << std::endl; //selectRNS(i); } } @@ -693,7 +693,7 @@ void ReachabilityMapWindow::setupEnvironment() if (!RuntimeEnvironment::getDataFileAbsolute(objectFile)) { - VR_ERROR << "No path to " << objectFile << endl; + VR_ERROR << "No path to " << objectFile << std::endl; return; } @@ -703,7 +703,7 @@ void ReachabilityMapWindow::setupEnvironment() } catch(const VirtualRobotException &e) { - VR_ERROR << "Could not load " << objectFile << endl; + VR_ERROR << "Could not load " << objectFile << std::endl; return; } @@ -734,7 +734,7 @@ void ReachabilityMapWindow::loadObjectFile(std::string filename) } catch(const VirtualRobotException &e) { - VR_ERROR << "Could not load " << filename << endl; + VR_ERROR << "Could not load " << filename << std::endl; return; } } diff --git a/VirtualRobot/examples/RobotViewer/RobotViewer.cpp b/VirtualRobot/examples/RobotViewer/RobotViewer.cpp index 05b9df68f34722c5d4b6e6d458b9ff386fb3ecdc..38e77a4adaf79e85a3ae9ba02917f7a1f8201339 100644 --- a/VirtualRobot/examples/RobotViewer/RobotViewer.cpp +++ b/VirtualRobot/examples/RobotViewer/RobotViewer.cpp @@ -35,7 +35,7 @@ int main(int argc, char* argv[]) VirtualRobot::RuntimeEnvironment::processCommandLine(argc, argv); VirtualRobot::RuntimeEnvironment::print(); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; // --robot "robots/iCub/iCub.xml" std::string filename("robots/ArmarIII/ArmarIII.xml"); //std::string filename("C:/Projects/MMM/mmmtools/data/Model/Winter/mmm.xml"); @@ -55,7 +55,7 @@ int main(int argc, char* argv[]) } } - cout << "Using robot at " << filename << endl; + std::cout << "Using robot at " << filename << std::endl; showRobotWindow rw(filename); diff --git a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp index 571c4e5e7d54a3754a602c1872cfbefd33eb5bc9..0e55487be00c6382fd27a1d1d0e4fe9ad363e6e7 100644 --- a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp +++ b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp @@ -29,7 +29,7 @@ float TIMER_MS = 30.0f; showRobotWindow::showRobotWindow(std::string& sRobotFilename) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; //this->setCaption(QString("ShowRobot - KIT - Humanoids Group")); //resize(1100, 768); @@ -85,9 +85,9 @@ void CShowRobotWindow::saveScreenshot() QImage i = w->grabFrameBuffer(); bool bRes = i.save(framefile.getString(), "PNG"); if (bRes) - cout << "wrote image " << counter << endl; + std::cout << "wrote image " << counter << std::endl; else - cout << "failed writing image " << counter << endl; + std::cout << "failed writing image " << counter << std::endl; }*/ @@ -331,18 +331,18 @@ void showRobotWindow::exportVRML() Eigen::Matrix4f m1 = robot->getRobotNode(t1)->getGlobalPose(); Eigen::Matrix4f m2 = robot->getRobotNode(t2)->getGlobalPose(); - cout << "global pose " << t1 <<":" << endl << m1 << endl; - cout << "global pose " << t2 <<":" << endl << m2 << endl; + std::cout << "global pose " << t1 <<":" << endl << m1 << std::endl; + std::cout << "global pose " << t2 <<":" << endl << m2 << std::endl; Eigen::Matrix4f parentM1 = robot->getRobotNode(t1)->getParent()->getGlobalPose(); Eigen::Matrix4f parentM2 = robot->getRobotNode(t2)->getParent()->getGlobalPose(); - cout << "global pose parent " << t1 <<":" << endl << parentM1 << endl; - cout << "global pose parent " << t2 <<":" << endl << parentM2 << endl; + std::cout << "global pose parent " << t1 <<":" << endl << parentM1 << std::endl; + std::cout << "global pose parent " << t2 <<":" << endl << parentM2 << std::endl; Eigen::Matrix4f localM1 = robot->getRobotNode(t1)->getLocalTransformation(); Eigen::Matrix4f localM2 = robot->getRobotNode(t2)->getLocalTransformation(); - cout << "local trafo " << t1 <<":" << endl << localM1 << endl; - cout << "local trafo " << t2 <<":" << endl << localM2 << endl; + std::cout << "local trafo " << t1 <<":" << endl << localM1 << std::endl; + std::cout << "local trafo " << t2 <<":" << endl << localM2 << std::endl; @@ -357,11 +357,11 @@ void showRobotWindow::exportVRML() m1 = parentM1 * localM1 /*getLocalTransformation()*/ * tmpRotMat1; m2 = parentM2 * localM2 /*getLocalTransformation()*/ * tmpRotMat2; - cout << "rot mat " << t1 <<":" << endl << tmpRotMat1 << endl; - cout << "rot mat " << t2 <<":" << endl << tmpRotMat2 << endl; + std::cout << "rot mat " << t1 <<":" << endl << tmpRotMat1 << std::endl; + std::cout << "rot mat " << t2 <<":" << endl << tmpRotMat2 << std::endl; - cout << "gp custom " << t1 <<":" << endl << m1 << endl; - cout << "gp custom " << t2 <<":" << endl << m2 << endl; + std::cout << "gp custom " << t1 <<":" << endl << m1 << std::endl; + std::cout << "gp custom " << t2 <<":" << endl << m2 << std::endl; @@ -379,9 +379,9 @@ void showRobotWindow::exportVRML() Eigen::Matrix4f gpr1 = robot->getRobotNode(knee1)->getGlobalPose(); Eigen::Matrix4f gpr2 = robot->getRobotNode(knee2)->getGlobalPose(); - cout << "gp " << knee1 <<":" << endl << gpr1 << endl; - cout << "gp " << knee2 <<":" << endl << gpr2 << endl; - cout << "gp knee1->knee2 :" << endl << robot->getRobotNode(knee1)->toLocalCoordinateSystem(robot->getRobotNode(knee2)->getGlobalPose()) << endl; + std::cout << "gp " << knee1 <<":" << endl << gpr1 << std::endl; + std::cout << "gp " << knee2 <<":" << endl << gpr2 << std::endl; + std::cout << "gp knee1->knee2 :" << endl << robot->getRobotNode(knee1)->toLocalCoordinateSystem(robot->getRobotNode(knee2)->getGlobalPose()) << std::endl; @@ -394,7 +394,7 @@ void showRobotWindow::exportVRML() RobotNodePtr tcp1 = robot->getRobotNode(n2); m1 = start1->toLocalCoordinateSystem(tcp1->getGlobalPose()); - cout << "trafo (" << n1 << " -> " << n2 << "):" << endl << m1 << endl; + std::cout << "trafo (" << n1 << " -> " << n2 << "):" << endl << m1 << std::endl; return; @@ -407,7 +407,7 @@ void showRobotWindow::exportVRML() RobotNodePtr tcp1 = robot->getRobotNode("Wrist 1 L"); Eigen::Matrix4f m1 = start1->toLocalCoordinateSystem(tcp1->getGlobalPose()); - cout << "OLD trafo (FW):" << endl << m1 << endl; + std::cout << "OLD trafo (FW):" << endl << m1 << std::endl; /* RobotFactory::robotStructureDef newStructure; @@ -465,7 +465,7 @@ void showRobotWindow::exportVRML() RobotNodePtr tcp2 = robot->getRobotNode("Wrist 1 L"); Eigen::Matrix4f m2 = start2->toLocalCoordinateSystem(tcp2->getGlobalPose()); - cout << "NEW trafo (INV):" << endl << m2 << endl; + std::cout << "NEW trafo (INV):" << endl << m2 << std::endl; return; @@ -485,7 +485,7 @@ void showRobotWindow::exportVRML() // Use currently selected node as origin robot->setGlobalPoseForRobotNode(robot->getRobotNode(UI.comboBoxJoint->currentText().toStdString()), Eigen::Matrix4f::Identity()); - VR_INFO << "Using selected node " << UI.comboBoxJoint->currentText().toStdString() << " as origin for exported model." << endl; + VR_INFO << "Using selected node " << UI.comboBoxJoint->currentText().toStdString() << " as origin for exported model." << std::endl; visualization = robot->getVisualization<CoinVisualization>(colModel); visualization->exportToVRML2(s); @@ -568,7 +568,7 @@ void showRobotWindow::updateRNSBox() void showRobotWindow::selectRNS(int nr) { currentRobotNodeSet.reset(); - cout << "Selecting RNS nr " << nr << endl; + std::cout << "Selecting RNS nr " << nr << std::endl; if (nr <= 0) { @@ -587,7 +587,7 @@ void showRobotWindow::selectRNS(int nr) currentRobotNodeSet = robotNodeSets[nr]; currentRobotNodes = currentRobotNodeSet->getAllRobotNodes(); std::cout << "COM:" << currentRobotNodeSet->getCoM(); - /*cout << "HIGHLIGHTING rns " << currentRobotNodeSet->getName() << endl; + /*cout << "HIGHLIGHTING rns " << currentRobotNodeSet->getName() << std::endl; if (visualization) { @@ -610,7 +610,7 @@ void showRobotWindow::selectJoint(int nr) } currentRobotNode.reset(); - cout << "Selecting Joint nr " << nr << endl; + std::cout << "Selecting Joint nr " << nr << std::endl; if (nr < 0 || nr >= (int)currentRobotNodes.size()) { @@ -650,7 +650,7 @@ void showRobotWindow::selectJoint(int nr) UI.checkBoxShowCoordSystem->setCheckState(Qt::Unchecked); } - cout << "HIGHLIGHTING node " << currentRobotNodes[nr]->getName() << endl; + std::cout << "HIGHLIGHTING node " << currentRobotNodes[nr]->getName() << std::endl; if (visualization) { @@ -680,9 +680,9 @@ void showRobotWindow::jointValueChanged(int pos) if (rnl && rnr) { - cout << "LEFT:" << endl; + std::cout << "LEFT:" << std::endl; MathTools::printMat(rnl->getGlobalPose()); - cout << "RIGHT:" << endl; + std::cout << "RIGHT:" << std::endl; MathTools::printMat(rnr->getGlobalPose()); } @@ -770,7 +770,7 @@ void showRobotWindow::testPerformance(RobotPtr robot, RobotNodeSetPtr rns) } clock_t end = clock(); float timeMS = (float)(end - start) / (float)CLOCKS_PER_SEC * 1000.0f; - VR_INFO << "Time (visu on, thread on): " << timeMS / (float)loops << endl; + VR_INFO << "Time (visu on, thread on): " << timeMS / (float)loops << std::endl; start = clock(); robot->setupVisualization(false, false); @@ -791,7 +791,7 @@ void showRobotWindow::testPerformance(RobotPtr robot, RobotNodeSetPtr rns) } end = clock(); timeMS = (float)(end - start) / (float)CLOCKS_PER_SEC * 1000.0f; - VR_INFO << "Time (visu off, thread on): " << timeMS / (float)loops << endl; + VR_INFO << "Time (visu off, thread on): " << timeMS / (float)loops << std::endl; start = clock(); robot->setupVisualization(true, false); @@ -809,7 +809,7 @@ void showRobotWindow::testPerformance(RobotPtr robot, RobotNodeSetPtr rns) } end = clock(); timeMS = (float)(end - start) / (float)CLOCKS_PER_SEC * 1000.0f; - VR_INFO << "Time (visu on, thread off): " << timeMS / (float)loops << endl; + VR_INFO << "Time (visu on, thread off): " << timeMS / (float)loops << std::endl; start = clock(); @@ -828,14 +828,14 @@ void showRobotWindow::testPerformance(RobotPtr robot, RobotNodeSetPtr rns) } end = clock(); timeMS = (float)(end - start) / (float)CLOCKS_PER_SEC * 1000.0f; - VR_INFO << "Time (visu off, thread off): " << timeMS / (float)loops << endl; + VR_INFO << "Time (visu off, thread off): " << timeMS / (float)loops << std::endl; } void showRobotWindow::loadRobot() { robotSep->removeAllChildren(); - cout << "Loading Robot from " << m_sRobotFilename << endl; + std::cout << "Loading Robot from " << m_sRobotFilename << std::endl; currentEEF.reset(); currentRobotNode.reset(); currentRobotNodes.clear(); @@ -850,7 +850,7 @@ void showRobotWindow::loadRobot() if (!importer) { - cout << " ERROR while grabbing importer" << endl; + std::cout << " ERROR while grabbing importer" << std::endl; return; } @@ -860,14 +860,14 @@ void showRobotWindow::loadRobot() } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return; } @@ -890,7 +890,7 @@ void showRobotWindow::loadRobot() l.push_back("Wrist 2 R"); robot = RobotFactory::cloneUniteSubsets(robot, "RobotWithUnitedHands", l); } - VR_INFO << "=========== PERFORMANCE orig ============" << endl; + VR_INFO << "=========== PERFORMANCE orig ============" << std::endl; testPerformance(robot, robot->getRobotNodeSet("Joints_Revolute")); if (robot->hasRobotNode("LWy_joint") && robot->hasRobotNode("RWy_joint")) { @@ -899,7 +899,7 @@ void showRobotWindow::loadRobot() l.push_back("RWy_joint"); robot = RobotFactory::cloneUniteSubsets(robot, "RobotWithUnitedHands", l); } - VR_INFO << "=========== PERFORMANCE clone ============" << endl; + VR_INFO << "=========== PERFORMANCE clone ============" << std::endl; testPerformance(robot, robot->getRobotNodeSet("Joints_Revolute"));// ("BPy_joint")); #endif @@ -1048,9 +1048,9 @@ void showRobotWindow::openHand() clock_t endT = clock(); float diffClock = (float)(((float)(endT - startT) / (float)CLOCKS_PER_SEC) * 1000.0f); - cout << "RobotNodes:" << rn.size() << endl; - cout << "Joints:" << rnJoints.size() << endl; - cout << "loops:" << loops << ". time (ms):" << diffClock << ". Per loop:" << diffClock / (float)loops << endl; + std::cout << "RobotNodes:" << rn.size() << std::endl; + std::cout << "Joints:" << rnJoints.size() << std::endl; + std::cout << "loops:" << loops << ". time (ms):" << diffClock << ". Per loop:" << diffClock / (float)loops << std::endl; } #endif @@ -1063,7 +1063,7 @@ void showRobotWindow::openHand() void showRobotWindow::selectEEF(int nr) { - cout << "Selecting EEF nr " << nr << endl; + std::cout << "Selecting EEF nr " << nr << std::endl; UI.comboBoxEndEffectorPS->clear(); currentEEF.reset(); @@ -1084,7 +1084,7 @@ void showRobotWindow::selectEEF(int nr) void showRobotWindow::selectPreshape(int nr) { - cout << "Selecting EEF preshape nr " << nr << endl; + std::cout << "Selecting EEF preshape nr " << nr << std::endl; if (!currentEEF || nr==0) return; diff --git a/VirtualRobot/examples/SceneViewer/SceneViewer.cpp b/VirtualRobot/examples/SceneViewer/SceneViewer.cpp index 9f73c645a335317178535ade5a91a00e610d64f2..a7962b9f3aa2cd762544fc7471674c312a3c17f3 100644 --- a/VirtualRobot/examples/SceneViewer/SceneViewer.cpp +++ b/VirtualRobot/examples/SceneViewer/SceneViewer.cpp @@ -29,7 +29,7 @@ int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "Simox Scene Viewer"); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; std::string filename("scenes/examples/SceneViewer/scene1.xml"); VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(filename); VirtualRobot::RuntimeEnvironment::considerKey("scene"); diff --git a/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp b/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp index 8ceb192483c11c3c3dd45009107caadc551d6a5f..092776c43c9ec84e33685f54166a1f0b9c79bd8d 100644 --- a/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp +++ b/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp @@ -28,7 +28,7 @@ float TIMER_MS = 30.0f; showSceneWindow::showSceneWindow(std::string& sSceneFile) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; sceneFile = sSceneFile; sceneSep = new SoSeparator; @@ -267,7 +267,7 @@ void showSceneWindow::loadScene() currentObject.reset(); currentRobot.reset(); currentTrajectory.reset(); - cout << "Loading Scene from " << sceneFile << endl; + std::cout << "Loading Scene from " << sceneFile << std::endl; scene.reset(); @@ -277,7 +277,7 @@ void showSceneWindow::loadScene() } catch (VirtualRobotException& e) { - cout << "Could not find valid scene in file " << sceneFile << endl; + std::cout << "Could not find valid scene in file " << sceneFile << std::endl; } if (!scene) @@ -291,7 +291,7 @@ void showSceneWindow::loadScene() if (mo) { - VR_INFO << "Loaded Manipulation object:" << endl; + VR_INFO << "Loaded Manipulation object:" << std::endl; mo->print(); scene.reset(new Scene(mo->getName())); scene->registerManipulationObject(mo); @@ -299,7 +299,7 @@ void showSceneWindow::loadScene() } catch (VirtualRobotException& e) { - cout << "Could not find valid manipulation object in file " << sceneFile << endl; + std::cout << "Could not find valid manipulation object in file " << sceneFile << std::endl; } } @@ -313,7 +313,7 @@ void showSceneWindow::loadScene() if (mo) { - VR_INFO << "Loaded obstacle:" << endl; + VR_INFO << "Loaded obstacle:" << std::endl; mo->print(); scene.reset(new Scene(mo->getName())); scene->registerObstacle(mo); @@ -321,41 +321,41 @@ void showSceneWindow::loadScene() } catch (VirtualRobotException& e) { - cout << "Could not find valid obstacle in file " << sceneFile << endl; + std::cout << "Could not find valid obstacle in file " << sceneFile << std::endl; } } if (!scene) { - cout << " ERROR while creating scene" << endl; + std::cout << " ERROR while creating scene" << std::endl; return; } /*std::vector<VirtualRobot::ManipulationObjectPtr> mo; mo = scene->getManipulationObjects(); - cout << "Printing " << mo.size() << " objects" << endl; + std::cout << "Printing " << mo.size() << " objects" << std::endl; for (size_t i=0;i<mo.size();i++) { mo[i]->print(); mo[i]->showCoordinateSystem(true); Eigen::Vector3f c = mo[i]->getCoMGlobal(); - cout << "com global: \n" << c << endl; + std::cout << "com global: \n" << c << std::endl; c = mo[i]->getCoMLocal(); - cout << "com local: \n" << c << endl; + std::cout << "com local: \n" << c << std::endl; //mo[i]->showBoundingBox(true); }*/ /*std::vector<VirtualRobot::ObstaclePtr> o; o = scene->getObstacles(); - cout << "Printing " << o.size() << " obstacles" << endl; + std::cout << "Printing " << o.size() << " obstacles" << std::endl; for (size_t i=0;i<o.size();i++) { o[i]->print(); o[i]->showCoordinateSystem(true); Eigen::Vector3f c = o[i]->getCoMGlobal(); - cout << "com global: \n" << c << endl; + std::cout << "com global: \n" << c << std::endl; c = o[i]->getCoMLocal(); - cout << "com local: \n" << c << endl; + std::cout << "com local: \n" << c << std::endl; //mo[i]->showBoundingBox(true); }*/ diff --git a/VirtualRobot/examples/loadRobot/loadRobot.cpp b/VirtualRobot/examples/loadRobot/loadRobot.cpp index 86e6a2acdc3c64d15c2f06c792c9c326fd45db5d..5c9639fbef4253effbd9b69e8c93f480dca538eb 100644 --- a/VirtualRobot/examples/loadRobot/loadRobot.cpp +++ b/VirtualRobot/examples/loadRobot/loadRobot.cpp @@ -26,8 +26,8 @@ int main(int argc, char* argv[]) std::map<RobotNodePtr, std::vector<std::string> > childrenMap; bool resInit = RobotFactory::initializeRobot(robot, robotNodes, childrenMap, node1); - cout << "resInit:" << resInit << endl; - cout << "First robot:" << endl; + std::cout << "resInit:" << resInit << std::endl; + std::cout << "First robot:" << std::endl; robot->print(); VirtualRobot::RuntimeEnvironment::considerKey("robot"); @@ -47,7 +47,7 @@ int main(int argc, char* argv[]) } } - cout << "Using robot at " << filename << endl; + std::cout << "Using robot at " << filename << std::endl; RobotPtr rob; try @@ -56,11 +56,11 @@ int main(int argc, char* argv[]) } catch (VirtualRobotException& e) { - cout << "Error: " << e.what() << endl; + std::cout << "Error: " << e.what() << std::endl; return -1; } - cout << "Second robot (XML):" << endl; + std::cout << "Second robot (XML):" << std::endl; if (rob) { @@ -68,6 +68,6 @@ int main(int argc, char* argv[]) } else { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; } } diff --git a/VirtualRobot/examples/loadURDFRobot/loadURDFobot.cpp b/VirtualRobot/examples/loadURDFRobot/loadURDFobot.cpp index cd050cecb028bfdf5d3c3c7a7be8534e05ea1e82..25db07bb69292fda96778a62222eb0a034550c80 100644 --- a/VirtualRobot/examples/loadURDFRobot/loadURDFobot.cpp +++ b/VirtualRobot/examples/loadURDFRobot/loadURDFobot.cpp @@ -35,7 +35,7 @@ int main(int /*argc*/, char* /*argv*/[]) RobotPtr r = f.loadFromFile(urdfFile); std::string outPath = std::filesystem::current_path().generic_string(); - cout << "Saving converted file to " << outPath << "/urdf_output.xml..." << endl; + std::cout << "Saving converted file to " << outPath << "/urdf_output.xml..." << std::endl; RobotIO::saveXML(r, "urdf_output.xml", outPath); } diff --git a/VirtualRobot/examples/reachability/reachabilityScene.cpp b/VirtualRobot/examples/reachability/reachabilityScene.cpp index 12b0e96ed847db9a0639f9b41a161daab4479e22..c66d17fc56042ee005a43ccf2cf864603b129949 100644 --- a/VirtualRobot/examples/reachability/reachabilityScene.cpp +++ b/VirtualRobot/examples/reachability/reachabilityScene.cpp @@ -45,7 +45,7 @@ void endlessExtend(std::string robotFile, std::string reachFile, int steps, unsi { threads = QThread::idealThreadCount() < 1 ? 1 : static_cast<unsigned int>(QThread::idealThreadCount()); } - VR_INFO << "Extending workspace information, saving each " << steps << " steps." << endl; + VR_INFO << "Extending workspace information, saving each " << steps << " steps." << std::endl; VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(robotFile); VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(reachFile); @@ -58,14 +58,14 @@ void endlessExtend(std::string robotFile, std::string reachFile, int steps, unsi } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return; } @@ -103,7 +103,7 @@ void endlessExtend(std::string robotFile, std::string reachFile, int steps, unsi if (!loadOK) { - VR_ERROR << "Could not load reach/manip file" << endl; + VR_ERROR << "Could not load reach/manip file" << std::endl; reachSpace.reset(); return; } @@ -148,8 +148,8 @@ int main(int argc, char* argv[]) { VirtualRobot::init(argc, argv, "Reachability Demo"); - cout << " --- START --- " << endl; - cout << "Hint: use '--extendReach true' to start a refinement of the reachability data. This is an endless mode which creates intermediate data files and that can be running e.g. over night." << std::endl; + std::cout << " --- START --- " << std::endl; + std::cout << "Hint: use '--extendReach true' to start a refinement of the reachability data. This is an endless mode which creates intermediate data files and that can be running e.g. over night." << std::endl; std::string filenameReach; #if defined(ICUB) @@ -184,7 +184,7 @@ int main(int argc, char* argv[]) VirtualRobot::RuntimeEnvironment::processCommandLine(argc, argv); VirtualRobot::RuntimeEnvironment::print(); - cout << " --- START --- " << endl; + std::cout << " --- START --- " << std::endl; filenameRob = VirtualRobot::RuntimeEnvironment::checkValidFileParameter("robot", filenameRob); @@ -196,12 +196,12 @@ int main(int argc, char* argv[]) if (!VirtualRobot::RuntimeEnvironment::toVector3f(axisStr, axisTCP)) { - cout << "Wrong axis definition:" << axisStr << endl; + std::cout << "Wrong axis definition:" << axisStr << std::endl; } } - cout << "Using robot at " << filenameRob << endl; - cout << "Using reachability file from " << filenameReach << endl; + std::cout << "Using robot at " << filenameRob << std::endl; + std::cout << "Using reachability file from " << filenameReach << std::endl; if (VirtualRobot::RuntimeEnvironment::hasValue("extendReach")) { diff --git a/VirtualRobot/examples/reachability/reachabilityWindow.cpp b/VirtualRobot/examples/reachability/reachabilityWindow.cpp index c3ba44bec768c855b292b1eafe86f03a3c2c5317..594933b7c17663ebbf4b6e14d893d89f62b1cf2a 100644 --- a/VirtualRobot/examples/reachability/reachabilityWindow.cpp +++ b/VirtualRobot/examples/reachability/reachabilityWindow.cpp @@ -33,7 +33,7 @@ float TIMER_MS = 30.0f; reachabilityWindow::reachabilityWindow(std::string& sRobotFile, std::string& reachFile, Eigen::Vector3f& axisTCP) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; this->axisTCP = axisTCP; robotFile = sRobotFile; @@ -220,7 +220,7 @@ void reachabilityWindow::reachVisu() WorkspaceRepresentation::WorkspaceCut2DPtr cutData = reachSpace->createCut(pos,reachSpace->getDiscretizeParameterTranslation(), true); - VR_INFO << "Slider pos: " << pos << ", maxEntry:" << reachSpace->getMaxSummedAngleReachablity() << ", cut maxCoeff:" << cutData->entries.maxCoeff() << endl; + VR_INFO << "Slider pos: " << pos << ", maxEntry:" << reachSpace->getMaxSummedAngleReachablity() << ", cut maxCoeff:" << cutData->entries.maxCoeff() << std::endl; SoNode *reachvisu2 = CoinVisualizationFactory::getCoinVisualization(cutData, VirtualRobot::ColorMap(VirtualRobot::ColorMap::eHot), Eigen::Vector3f::UnitZ(), reachSpace->getMaxSummedAngleReachablity(), minAngle, maxAngle); visualisationNode->addChild(reachvisu2); @@ -313,7 +313,7 @@ void reachabilityWindow::updateRNSBox() void reachabilityWindow::selectRNS(int nr) { currentRobotNodeSet.reset(); - cout << "Selecting RNS nr " << nr << endl; + std::cout << "Selecting RNS nr " << nr << std::endl; std::string tcp = "<not set>"; if (nr < 0 || nr >= (int)robotNodeSets.size()) @@ -372,7 +372,7 @@ void reachabilityWindow::jointValueChanged(int pos) void reachabilityWindow::selectJoint(int nr) { currentRobotNode.reset(); - cout << "Selecting Joint nr " << nr << endl; + std::cout << "Selecting Joint nr " << nr << std::endl; if (nr < 0 || nr >= (int)allRobotNodes.size()) { @@ -432,7 +432,7 @@ void reachabilityWindow::selectRobot() void reachabilityWindow::loadRobot() { robotVisuSep->removeAllChildren(); - cout << "Loading Scene from " << robotFile << endl; + std::cout << "Loading Scene from " << robotFile << std::endl; try { @@ -440,14 +440,14 @@ void reachabilityWindow::loadRobot() } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return; } @@ -461,12 +461,12 @@ void reachabilityWindow::loadRobot() { if (i->isKinematicChain()) { - VR_INFO << " RNS <" << i->getName() << "> is a valid kinematic chain" << endl; + VR_INFO << " RNS <" << i->getName() << "> is a valid kinematic chain" << std::endl; robotNodeSets.push_back(i); } else { - VR_INFO << " RNS <" << i->getName() << "> is not a valid kinematic chain" << endl; + VR_INFO << " RNS <" << i->getName() << "> is not a valid kinematic chain" << std::endl; } } @@ -488,7 +488,7 @@ void reachabilityWindow::extendReach() if (!reachSpace) { - cout << " Please load/create reachability data first..." << endl; + std::cout << " Please load/create reachability data first..." << std::endl; return; } @@ -628,9 +628,9 @@ void reachabilityWindow::fillHoles() return; } - cout << "filling holes of reachability space" << endl; + std::cout << "filling holes of reachability space" << std::endl; int res = reachSpace->fillHoles(); - cout << "Filled " << res << " voxels" << endl; + std::cout << "Filled " << res << " voxels" << std::endl; reachSpace->print(); } @@ -641,7 +641,7 @@ void reachabilityWindow::binarize() return; } - cout << "Binarizing reachability space" << endl; + std::cout << "Binarizing reachability space" << std::endl; reachSpace->binarize(); reachSpace->print(); } @@ -654,13 +654,13 @@ void reachabilityWindow::computeVolume() VirtualRobot::WorkspaceRepresentation::VolumeInfo vi; vi = reachSpace->computeVolumeInformation(); - cout << "Reachability Volume Information:" << endl; - cout << "Nr 3d Voxels:" << vi.voxelCount3D << endl; - cout << "Nr filled 3d Voxels:" << vi.filledVoxelCount3D << endl; - cout << "Nr border 3d Voxels:" << vi.borderVoxelCount3D << endl; - cout << "Volume per 3d Voxel:" << vi.volumeVoxel3D << " m^3" << endl; - cout << "Volume of all filled 3d Voxels:" << vi.volumeFilledVoxels3D << " m^3" << endl; - cout << "Volume of filledVoxels - borderVoxels*0.5:" << vi.volume3D << " m^3" << endl; + std::cout << "Reachability Volume Information:" << std::endl; + std::cout << "Nr 3d Voxels:" << vi.voxelCount3D << std::endl; + std::cout << "Nr filled 3d Voxels:" << vi.filledVoxelCount3D << std::endl; + std::cout << "Nr border 3d Voxels:" << vi.borderVoxelCount3D << std::endl; + std::cout << "Volume per 3d Voxel:" << vi.volumeVoxel3D << " m^3" << std::endl; + std::cout << "Volume of all filled 3d Voxels:" << vi.volumeFilledVoxels3D << " m^3" << std::endl; + std::cout << "Volume of filledVoxels - borderVoxels*0.5:" << vi.volume3D << " m^3" << std::endl; } void reachabilityWindow::saveReach() @@ -721,7 +721,7 @@ void reachabilityWindow::loadReachFile(std::string filename) if (!loadOK) { - VR_ERROR << "Could not load reach/manip file" << endl; + VR_ERROR << "Could not load reach/manip file" << std::endl; reachSpace.reset(); return; } @@ -730,15 +730,15 @@ void reachabilityWindow::loadReachFile(std::string filename) if (reachSpace->getNodeSet()) { - cout << "Using RNS: " << reachSpace->getNodeSet()->getName() << endl; + std::cout << "Using RNS: " << reachSpace->getNodeSet()->getName() << std::endl; for (size_t i = 0; i < robotNodeSets.size(); i++) { - cout << "checking " << robotNodeSets[i]->getName() << endl; + std::cout << "checking " << robotNodeSets[i]->getName() << std::endl; if (robotNodeSets[i] == reachSpace->getNodeSet()) { - cout << "Found RNS.." << endl; + std::cout << "Found RNS.." << std::endl; UI.comboBoxRNS->setCurrentIndex(i); selectRNS(i); } diff --git a/VirtualRobot/examples/stability/stabilityWindow.cpp b/VirtualRobot/examples/stability/stabilityWindow.cpp index cc100b538a85faa15586b2d787db97d7e327a760..da10a25e97ec9e4743ac8c19347edd2f4d4d1573 100644 --- a/VirtualRobot/examples/stability/stabilityWindow.cpp +++ b/VirtualRobot/examples/stability/stabilityWindow.cpp @@ -39,7 +39,7 @@ float TIMER_MS = 30.0f; stabilityWindow::stabilityWindow(std::string& sRobotFile) : QMainWindow(nullptr) { - VR_INFO << " start " << endl; + VR_INFO << " start " << std::endl; robotFile = sRobotFile; useColModel = false; @@ -375,12 +375,12 @@ void stabilityWindow::updateRNSBox() { //if (allRNS[i]->isKinematicChain()) //{ - //VR_INFO << " RNS <" << allRNS[i]->getName() << "> is a valid kinematic chain" << endl; + //VR_INFO << " RNS <" << allRNS[i]->getName() << "> is a valid kinematic chain" << std::endl; robotNodeSets.push_back(i); UI.comboBoxRNS->addItem(QString(i->getName().c_str())); /*} else { - VR_INFO << " RNS <" << allRNS[i]->getName() << "> is not a valid kinematic chain" << endl; + VR_INFO << " RNS <" << allRNS[i]->getName() << "> is not a valid kinematic chain" << std::endl; }*/ } @@ -397,7 +397,7 @@ void stabilityWindow::updateRNSBox() void stabilityWindow::selectRNS(int nr) { currentRobotNodeSet.reset(); - cout << "Selecting RNS nr " << nr << endl; + std::cout << "Selecting RNS nr " << nr << std::endl; if (nr <= 0) { @@ -491,7 +491,7 @@ void stabilityWindow::jointValueChanged(int pos) void stabilityWindow::selectJoint(int nr) { currentRobotNode.reset(); - cout << "Selecting Joint nr " << nr << endl; + std::cout << "Selecting Joint nr " << nr << std::endl; if (nr < 0 || nr >= (int)currentRobotNodes.size()) { @@ -532,7 +532,7 @@ void stabilityWindow::selectRobot() void stabilityWindow::loadRobot() { robotVisuSep->removeAllChildren(); - cout << "Loading Scene from " << robotFile << endl; + std::cout << "Loading Scene from " << robotFile << std::endl; try { @@ -540,14 +540,14 @@ void stabilityWindow::loadRobot() } catch (VirtualRobotException& e) { - cout << " ERROR while creating robot" << endl; - cout << e.what(); + std::cout << " ERROR while creating robot" << std::endl; + std::cout << e.what(); return; } if (!robot) { - cout << " ERROR while creating robot" << endl; + std::cout << " ERROR while creating robot" << std::endl; return; }