diff --git a/GraspPlanning/ConvexHullGenerator.cpp b/GraspPlanning/ConvexHullGenerator.cpp index c176c2f712c682d6476cc26b143076754d93450e..32062cdbf4b9584f6a0e136f863b42eb9323186e 100644 --- a/GraspPlanning/ConvexHullGenerator.cpp +++ b/GraspPlanning/ConvexHullGenerator.cpp @@ -183,9 +183,9 @@ namespace GraspStudio double pCenter[3]; - for (int u = 0; u < 3; u++) + for (double & u : pCenter) { - pCenter[u] = 0; + u = 0; } int nVcertexCount = 0; @@ -200,9 +200,9 @@ namespace GraspStudio } if (nVcertexCount > 0) - for (int u = 0; u < 3; u++) + for (double & u : pCenter) { - pCenter[u] /= (float)nVcertexCount; + u /= (float)nVcertexCount; } result->center[0] = pCenter[0]; @@ -360,16 +360,16 @@ namespace GraspStudio /*int convexNumVert2 =*/ qh_setsize(qh_facetvertices(facet_list, NULL, false)); double pCenter[6]; - for (int u = 0; u < 6; u++) + for (double & u : pCenter) { - pCenter[u] = 0; + u = 0; } double pZero[6]; - for (int u = 0; u < 6; u++) + for (double & u : pZero) { - pZero[u] = 0; + u = 0; } int nVcertexCount = 0; @@ -384,9 +384,9 @@ namespace GraspStudio } if (nVcertexCount > 0) - for (int u = 0; u < 6; u++) + for (double & u : pCenter) { - pCenter[u] /= (float)nVcertexCount; + u /= (float)nVcertexCount; } result->center.p[0] = pCenter[0]; diff --git a/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.cpp b/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.cpp index 7b14bff3ed0c8b5a241094625abec01cd7dd660c..4dcb65f444fce35ed34bbe1e8f4002b58fcf21de 100644 --- a/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.cpp +++ b/GraspPlanning/GraspQuality/GraspEvaluationPoseUncertainty.cpp @@ -244,18 +244,18 @@ GraspEvaluationPoseUncertainty::PoseEvalResults GraspEvaluationPoseUncertainty:: return res; res.numPosesTested = results.size(); - for (size_t i=0;i<results.size();i++) + for (auto & result : results) { - if (results.at(i).initialCollision) + if (result.initialCollision) { res.numColPoses++; } else { res.numValidPoses++; - res.avgQuality += results.at(i).quality; - res.avgQualityCol += results.at(i).quality; - if (results.at(i).forceClosure) + res.avgQuality += result.quality; + res.avgQualityCol += result.quality; + if (result.forceClosure) { res.forceClosureRate += 1.0f; res.forceClosureRateCol += 1.0f; diff --git a/GraspPlanning/GraspQuality/GraspQualityMeasure.cpp b/GraspPlanning/GraspQuality/GraspQualityMeasure.cpp index 2b48150237a5f4b7b84d0d28368485cbfab26d11..62d3339bcdfe0e6eb64919c4372d9bc9085f8ef6 100644 --- a/GraspPlanning/GraspQuality/GraspQualityMeasure.cpp +++ b/GraspPlanning/GraspQuality/GraspQualityMeasure.cpp @@ -100,10 +100,10 @@ namespace GraspStudio return p; } - for (int i = 0; i < (int)sampledObjectPoints.size(); i++) + for (auto & sampledObjectPoint : sampledObjectPoints) { - p.p += sampledObjectPoints[i].p; - p.n += sampledObjectPoints[i].n; + p.p += sampledObjectPoint.p; + p.n += sampledObjectPoint.n; } p.p /= (float)sampledObjectPoints.size(); diff --git a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp index 060a40c04ecac741f793de1c61e181a7e202c9ef..6d64559d73c7f8b4470824b36c1ac2c63dc81e49 100644 --- a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp +++ b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpace.cpp @@ -296,10 +296,10 @@ namespace GraspStudio faceCenter.p.setZero(); faceCenter.n.setZero(); - for (int j = 0; j < 6; j++) + for (int j : faceIter->id) { - faceCenter.p += (convexHullGWS->vertices)[faceIter->id[j]].p; - faceCenter.n += (convexHullGWS->vertices)[faceIter->id[j]].n; + faceCenter.p += (convexHullGWS->vertices)[j].p; + faceCenter.n += (convexHullGWS->vertices)[j].n; } faceCenter.p /= 6.0f; @@ -406,15 +406,15 @@ namespace GraspStudio float fRes = FLT_MAX; int nWrongFacets = 0; - for (size_t i = 0; i < ch->faces.size(); i++) + for (auto & face : ch->faces) { - if (ch->faces[i].distNormCenter > 0) + if (face.distNormCenter > 0) { nWrongFacets++; } - else if (-(ch->faces[i].distNormCenter) < fRes) + else if (-(face.distNormCenter) < fRes) { - fRes = -(ch->faces[i].distNormCenter); + fRes = -(face.distNormCenter); } } diff --git a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp index 436b632d7f5f95f851081d068c8abc0fc72fd127..7fc17b04544212c14992021d0367eb058c59d2e0 100644 --- a/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp +++ b/GraspPlanning/GraspQuality/GraspQualityMeasureWrenchSpaceNotNormalized.cpp @@ -227,10 +227,10 @@ namespace GraspStudio faceCenter.p.setZero(); faceCenter.n.setZero(); - for (int j = 0; j < 6; j++) + for (int j : faceIter->id) { - faceCenter.p += (convexHullGWS->vertices)[faceIter->id[j]].p; - faceCenter.n += (convexHullGWS->vertices)[faceIter->id[j]].n; + faceCenter.p += (convexHullGWS->vertices)[j].p; + faceCenter.n += (convexHullGWS->vertices)[j].n; } faceCenter.p /= 6.0f; @@ -285,9 +285,9 @@ namespace GraspStudio float fRes = FLT_MAX; int nWrongFacets = 0; - for (size_t i = 0; i < ch->faces.size(); i++) + for (auto & face : ch->faces) { - const auto dist = ch->faces[i].distNormCenter; + const auto dist = face.distNormCenter; if (dist > 0) { //outside diff --git a/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.cpp b/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.cpp index 5ae6bf4e5129bda59567db8fb6354890640d92f5..51ccb15fddd6e68a262cb159793d44271e120ce0 100644 --- a/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.cpp +++ b/GraspPlanning/Visualization/CoinVisualization/CoinConvexHullVisualization.cpp @@ -215,17 +215,17 @@ namespace GraspStudio for (int i = 0; i < nFaces; i++) { - for (int j = 0; j < 6; j++) + for (int j : convHull->faces[i].id) { if (buseFirst3Coords) { //v[j] = convHull->vertices.at(convHull->faces[i].id[j]).p; - vProjectedPoints.push_back(convHull->vertices[ convHull->faces[i].id[j] ].p); + vProjectedPoints.push_back(convHull->vertices[ j ].p); } else { //v[j] = convHull->vertices.at(convHull->faces[i].id[j]).n; - vProjectedPoints.push_back(convHull->vertices[ convHull->faces[i].id[j] ].n); + vProjectedPoints.push_back(convHull->vertices[ j ].n); } } diff --git a/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.cpp b/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.cpp index 871f76570a448e96d3357b19f7463a82d505180a..e9acf17b6f8b159e8222a6cd38657a06621386dc 100644 --- a/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.cpp +++ b/GraspPlanning/examples/GraspPlanner/GraspPlannerWindow.cpp @@ -262,15 +262,15 @@ void GraspPlannerWindow::buildVisu() } // add approach dir visu - for (size_t i = 0; i < contacts.size(); i++) + for (auto & contact : contacts) { SoSeparator* s = new SoSeparator; Eigen::Matrix4f ma; ma.setIdentity(); - ma.block(0, 3, 3, 1) = contacts[i].contactPointFingerGlobal; + ma.block(0, 3, 3, 1) = contact.contactPointFingerGlobal; SoMatrixTransform* m = CoinVisualizationFactory::getMatrixTransformScaleMM2M(ma); s->addChild(m); - s->addChild(CoinVisualizationFactory::CreateArrow(contacts[i].approachDirectionGlobal, 10.0f, 1.0f)); + s->addChild(CoinVisualizationFactory::CreateArrow(contact.approachDirectionGlobal, 10.0f, 1.0f)); frictionConeSep->addChild(s); } } diff --git a/GraspPlanning/examples/GraspQuality/GraspQualityWindow.cpp b/GraspPlanning/examples/GraspQuality/GraspQualityWindow.cpp index 744b1cf4c726cbc9b8e14bfdacdad6e6b6b40aee..989797f4e6af118667409bbaffb529989b5b13e5 100644 --- a/GraspPlanning/examples/GraspQuality/GraspQualityWindow.cpp +++ b/GraspPlanning/examples/GraspQuality/GraspQualityWindow.cpp @@ -488,9 +488,9 @@ void GraspQualityWindow::setEEFComboBox() robot->getEndEffectors(eefs); - for (size_t i = 0; i < eefs.size(); i++) + for (auto & eef : eefs) { - QString nameEEF(eefs[i]->getName().c_str()); + QString nameEEF(eef->getName().c_str()); UI.comboBoxEEF->addItem(nameEEF); } } diff --git a/MotionPlanning/ApproachDiscretization.cpp b/MotionPlanning/ApproachDiscretization.cpp index 425d8883b83eb0f37dcf790ef2e11034a03b37d3..c2999018db6af6ad8d007c6d3c58c9a10f121787 100644 --- a/MotionPlanning/ApproachDiscretization.cpp +++ b/MotionPlanning/ApproachDiscretization.cpp @@ -93,15 +93,15 @@ namespace Saba zeroPt.setZero(); VirtualRobot::SphereApproximator::FaceIndex faceIndx = sphere.mapVerticeIndxToFaceIndx[nIndex]; - for (int i = 0; i < (int)faceIndx.faceIds.size(); i++) + for (int faceId : faceIndx.faceIds) { - VirtualRobot::MathTools::TriangleFace f = sphere.faces[faceIndx.faceIds[i]]; + VirtualRobot::MathTools::TriangleFace f = sphere.faces[faceId]; //if (sphereGenerator->check_intersect_tri(sphere.vertices[f.n1],sphere.m_Vertices[f.m_n2],sphere.m_Vertices[f.m_n3],zeroPt,Pose1,storeIntPoint)) if (sphereGenerator->check_intersect_tri(sphere.vertices[f.id1], sphere.vertices[f.id2], sphere.vertices[f.id3], zeroPt, dir, storeIntPoint)) { //MarkFace(FaceIndx.m_faceIds[i],true); - return faceIndx.faceIds[i]; + return faceId; } } diff --git a/MotionPlanning/CSpace/CSpace.cpp b/MotionPlanning/CSpace/CSpace.cpp index 5c4ff7df7e700bfdab6802e4cb56aef7ea45db29..ca450d4210935ff30f39f1296aee835a00e70d72 100644 --- a/MotionPlanning/CSpace/CSpace.cpp +++ b/MotionPlanning/CSpace/CSpace.cpp @@ -842,9 +842,9 @@ namespace Saba bool CSpace::isSatisfyingConstraints(const Eigen::VectorXf& config) { - for (size_t i = 0; i < constraints.size(); i++) + for (auto & constraint : constraints) { - if (!constraints[i]->isValid(config)) + if (!constraint->isValid(config)) { return false; } diff --git a/MotionPlanning/CSpace/CSpaceTree.cpp b/MotionPlanning/CSpace/CSpaceTree.cpp index 8e2a632b2ce2bec7998c854b4a56bf59d63e7170..126ebb53c8e64a4cac551a52842389b38aaecec4 100644 --- a/MotionPlanning/CSpace/CSpaceTree.cpp +++ b/MotionPlanning/CSpace/CSpaceTree.cpp @@ -362,10 +362,10 @@ namespace Saba CSpaceNodePtr actualNode; - for (unsigned int i = 0; i < nodes.size(); i++) + for (const auto & node : nodes) { // save ID, configuration and parentID of each node in one row - actualNode = nodes[i]; + actualNode = node; file << actualNode->ID << " "; for (unsigned int j = 0; j < dimension; j++) diff --git a/MotionPlanning/Planner/BiRrt.cpp b/MotionPlanning/Planner/BiRrt.cpp index 79188b0cbfbd31ac8069439fe414ba9bac316453..e77b3af19a2f4ba156a8a85321b2e39b0c3841c9 100644 --- a/MotionPlanning/Planner/BiRrt.cpp +++ b/MotionPlanning/Planner/BiRrt.cpp @@ -353,14 +353,14 @@ namespace Saba // Create the CSpacePath, first start node till bridgeover node, then bridgeover node till goal node solution.reset(new CSpacePath(cspace)); - for (unsigned int i = 0; i < tmpSol.size(); i++) + for (int i : tmpSol) { - solution->addPoint(tree->getNode(tmpSol[i])->configuration); + solution->addPoint(tree->getNode(i)->configuration); } - for (unsigned int i = 0; i < tmpSol2.size(); i++) + for (int i : tmpSol2) { - solution->addPoint(tree2->getNode(tmpSol2[i])->configuration); + solution->addPoint(tree2->getNode(i)->configuration); } if (!bQuiet) diff --git a/MotionPlanning/Planner/GraspRrt.cpp b/MotionPlanning/Planner/GraspRrt.cpp index 4c56eff29f1a8d27159cccf3557b1532c88436ee..74c84bc7aa9092960924a80b2e3145370070811d 100644 --- a/MotionPlanning/Planner/GraspRrt.cpp +++ b/MotionPlanning/Planner/GraspRrt.cpp @@ -912,11 +912,11 @@ namespace Saba VirtualRobot::EndEffector::ContactInfoVector contacts; // we only need the targetObject contacts - for (size_t i = 0; i < contactsAll.size(); i++) + for (auto & i : contactsAll) { - if (contactsAll[i].obstacle == targetObject) + if (i.obstacle == targetObject) { - contacts.push_back(contactsAll[i]); + contacts.push_back(i); } } @@ -929,9 +929,9 @@ namespace Saba cout << __FUNCTION__ << ": Low number of contacts -> Zero Grasp Score " << endl; cout << "Fingers: " ; - for (int i = 0; i < (int)contacts.size(); i++) + for (auto & contact : contacts) { - cout << contacts[i].actor->getName() << ", "; + cout << contact.actor->getName() << ", "; } cout << endl; diff --git a/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.cpp b/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.cpp index 507c8d6b4e27024ca19c55484e37138ecd7474f3..13474d576b32d52752be58f391ebd37d6694dac3 100644 --- a/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.cpp +++ b/MotionPlanning/Visualization/CoinVisualization/CoinRrtWorkspaceVisualization.cpp @@ -262,9 +262,9 @@ namespace Saba Eigen::Vector3f p; Eigen::Vector3f p2; - for (unsigned int i = 0; i < nodes.size(); i++) + for (const auto & node : nodes) { - actualNode = nodes[i]; + actualNode = node; // get tcp coords: robot->setJointValues(robotNodeSet, actualNode->configuration); @@ -278,10 +278,10 @@ namespace Saba } - for (unsigned int i = 0; i < nodes.size(); i++) + for (const auto & node : nodes) { - actualNode = nodes[i]; + actualNode = node; parentid = actualNode->parentID; // create 3D model for nodes diff --git a/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp b/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp index 4d0af86905c0cac2d7c6d281428384a59d1b1478..4033f366b4de47eec8645886955c9e193f6b825a 100644 --- a/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp +++ b/MotionPlanning/examples/GraspRRT/GraspRrtWindow.cpp @@ -215,10 +215,10 @@ void GraspRrtWindow::buildVisu() { SoSeparator* eefVisu = CoinVisualizationFactory::CreateEndEffectorVisualization(eef); - for (size_t i = 0; i < grasps.size(); i++) + for (auto & grasp : grasps) { - Eigen::Matrix4f m = grasps[i]->getTcpPoseGlobal(targetObject->getGlobalPose()); + Eigen::Matrix4f m = grasp->getTcpPoseGlobal(targetObject->getGlobalPose()); SoSeparator* sep1 = new SoSeparator(); SoMatrixTransform* mt = CoinVisualizationFactory::getMatrixTransformScaleMM2M(m); sep1->addChild(mt); @@ -309,9 +309,9 @@ void GraspRrtWindow::loadScene() UI.comboBoxStart->clear(); - for (size_t i = 0; i < configs.size(); i++) + for (auto & config : configs) { - QString qtext = configs[i]->getName().c_str(); + QString qtext = config->getName().c_str(); UI.comboBoxStart->addItem(qtext); } @@ -330,9 +330,9 @@ void GraspRrtWindow::loadScene() UI.comboBoxGoal->clear(); - for (size_t i = 0; i < obstacles.size(); i++) + for (auto & obstacle : obstacles) { - QString qtext = obstacles[i]->getName().c_str(); + QString qtext = obstacle->getName().c_str(); UI.comboBoxGoal->addItem(qtext); } @@ -345,9 +345,9 @@ void GraspRrtWindow::loadScene() UI.comboBoxColModelEnv->clear(); QString qtext; - for (size_t i = 0; i < soss.size(); i++) + for (auto & sos : soss) { - qtext = soss[i]->getName().c_str(); + qtext = sos->getName().c_str(); UI.comboBoxColModelEnv->addItem(qtext); } @@ -384,9 +384,9 @@ void GraspRrtWindow::loadScene() UI.comboBoxColModelRobotStatic->clear(); UI.comboBoxRNS->clear(); - for (size_t i = 0; i < rnss.size(); i++) + for (auto & rns : rnss) { - qtext = rnss[i]->getName().c_str(); + qtext = rns->getName().c_str(); UI.comboBoxColModelRobot->addItem(qtext); UI.comboBoxColModelRobotStatic->addItem(qtext); UI.comboBoxRNS->addItem(qtext); diff --git a/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp b/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp index a4fe17150cab0557919ac8211bb3c99bcc3c2dfa..9574ca04bd2f096a9f9e7a6964cf09435ff610d5 100644 --- a/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp +++ b/MotionPlanning/examples/IKRRT/IKRRTWindow.cpp @@ -311,9 +311,9 @@ void IKRRTWindow::buildVisu() if (obstacles.size() > 0) { - for (size_t i = 0; i < obstacles.size(); i++) + for (const auto & obstacle : obstacles) { - SoNode* visualisationNode = CoinVisualizationFactory::getCoinVisualization(obstacles[i], colModel); + SoNode* visualisationNode = CoinVisualizationFactory::getCoinVisualization(obstacle, colModel); if (visualisationNode) { diff --git a/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp b/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp index 6f8d18e7be1040c0040cede3b42d995a9944f70c..4182a92ff4559f84542e00d1267637cb0a5bf0eb 100644 --- a/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp +++ b/MotionPlanning/examples/MultiThreadedPlanning/MTPlanningScenery.cpp @@ -77,9 +77,9 @@ MTPlanningScenery::~MTPlanningScenery() void MTPlanningScenery::reset() { - for (int i = 0; i < (int)robots.size(); i++) + for (auto & robot : robots) { - robots[i].reset(); + robot.reset(); } robots.clear(); @@ -94,30 +94,30 @@ void MTPlanningScenery::reset() stopOptimizing(); } - for (int i = 0; i < (int)planners.size(); i++) + for (auto & planner : planners) { - planners[i].reset(); + planner.reset(); } planners.clear(); - for (int i = 0; i < (int)CSpaces.size(); i++) + for (auto & CSpace : CSpaces) { - CSpaces[i].reset(); + CSpace.reset(); } CSpaces.clear(); - for (int i = 0; i < (int)planningThreads.size(); i++) + for (auto & planningThread : planningThreads) { - planningThreads[i].reset(); + planningThread.reset(); } planningThreads.clear(); - for (int i = 0; i < (int)optimizeThreads.size(); i++) + for (auto & optimizeThread : optimizeThreads) { - optimizeThreads[i].reset(); + optimizeThread.reset(); } optimizeThreads.clear(); @@ -125,11 +125,11 @@ void MTPlanningScenery::reset() solutions.clear(); optiSolutions.clear(); - for (int i = 0; i < (int)visualisations.size(); i++) + for (auto & visualisation : visualisations) { - if (visualisations[i] != NULL) + if (visualisation != NULL) { - sceneSep->removeChild(visualisations[i]); + sceneSep->removeChild(visualisation); } } @@ -451,14 +451,14 @@ void MTPlanningScenery::stopPlanning() { cout << "Stopping " << planningThreads.size() << " planning threads..." << endl; - for (unsigned int i = 0; i < planningThreads.size(); i++) + for (auto & planningThread : planningThreads) { - planningThreads[i]->stop(); + planningThread->stop(); } - for (unsigned int i = 0; i < robots.size(); i++) + for (auto & robot : robots) { - robots[i]->setUpdateVisualization(true); + robot->setUpdateVisualization(true); } cout << "... done" << endl; @@ -476,14 +476,14 @@ void MTPlanningScenery::stopOptimizing() cout << "Stopping " << optimizeThreads.size() << " optimizing threads..." << endl; - for (int i = 0; i < (int)optimizeThreads.size(); i++) + for (auto & optimizeThread : optimizeThreads) { - optimizeThreads[i]->stop(); + optimizeThread->stop(); } - for (int i = 0; i < (int)robots.size(); i++) + for (auto & robot : robots) { - robots[i]->setUpdateVisualization(true); + robot->setUpdateVisualization(true); } cout << "...done" << endl; @@ -501,14 +501,14 @@ void MTPlanningScenery::startPlanning() cout << "Starting " << planningThreads.size() << " planning threads..." << endl; - for (unsigned int i = 0; i < robots.size(); i++) + for (auto & robot : robots) { - robots[i]->setUpdateVisualization(false); + robot->setUpdateVisualization(false); } - for (unsigned int i = 0; i < planningThreads.size(); i++) + for (auto & planningThread : planningThreads) { - planningThreads[i]->start(); + planningThread->start(); } cout << "... done" << endl; @@ -537,9 +537,9 @@ void MTPlanningScenery::startOptimizing() if (plannersStarted) { - for (int i = 0; i < (int)planningThreads.size(); i++) + for (auto & planningThread : planningThreads) { - if (planningThreads[i]->isRunning()) + if (planningThread->isRunning()) { cout << "Planning is not finish!..." << endl; return; @@ -564,16 +564,16 @@ void MTPlanningScenery::startOptimizing() int j = 0; - for (unsigned int i = 0; i < robots.size(); i++) + for (auto & robot : robots) { - robots[i]->setUpdateVisualization(false); + robot->setUpdateVisualization(false); } - for (unsigned int i = 0; i < optimizeThreads.size(); i++) + for (auto & optimizeThread : optimizeThreads) { - if (optimizeThreads[i]) + if (optimizeThread) { - optimizeThreads[i]->start(SHORTEN_LOOP); + optimizeThread->start(SHORTEN_LOOP); j++; } } @@ -852,10 +852,8 @@ void MTPlanningScenery::getThreadCount(int& nWorking, int& nIdle) nWorking = 0; nIdle = 0; - for (unsigned int i = 0; i < planningThreads.size(); i++) + for (auto pThread : planningThreads) { - PlanningThreadPtr pThread = planningThreads[i]; - if (pThread->isRunning()) { nWorking++; @@ -873,10 +871,8 @@ void MTPlanningScenery::getOptimizeThreadCount(int& nWorking, int& nIdle) nWorking = 0; nIdle = 0; - for (unsigned int i = 0; i < optimizeThreads.size(); i++) + for (auto pOptiThread : optimizeThreads) { - PathProcessingThreadPtr pOptiThread = optimizeThreads[i]; - if (pOptiThread && pOptiThread->isRunning()) { nWorking++; diff --git a/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp b/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp index e8e8b3dd4f96c5ffe90434010ad60bfe49c46167..b1be17b31f65b2786743c9c7d93399c99d27af3a 100644 --- a/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp +++ b/MotionPlanning/examples/RrtGui/RrtGuiWindow.cpp @@ -294,9 +294,9 @@ void RrtGuiWindow::loadScene() UI.comboBoxGoal->clear(); UI.comboBoxStart->clear(); - for (size_t i = 0; i < configs.size(); i++) + for (auto & config : configs) { - QString qtext = configs[i]->getName().c_str(); + QString qtext = config->getName().c_str(); UI.comboBoxStart->addItem(qtext); UI.comboBoxGoal->addItem(qtext); } @@ -310,9 +310,9 @@ void RrtGuiWindow::loadScene() UI.comboBoxColModelEnv->clear(); QString qtext; - for (size_t i = 0; i < soss.size(); i++) + for (auto & sos : soss) { - qtext = soss[i]->getName().c_str(); + qtext = sos->getName().c_str(); UI.comboBoxColModelEnv->addItem(qtext); } @@ -324,9 +324,9 @@ void RrtGuiWindow::loadScene() UI.comboBoxColModelRobotStatic->clear(); UI.comboBoxRNS->clear(); - for (size_t i = 0; i < rnss.size(); i++) + for (auto & rns : rnss) { - qtext = rnss[i]->getName().c_str(); + qtext = rns->getName().c_str(); UI.comboBoxColModelRobot->addItem(qtext); UI.comboBoxColModelRobotStatic->addItem(qtext); UI.comboBoxRNS->addItem(qtext); diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp index b343fc4ee66a88267c75b0b5440c7f0aa96fe18c..cb39d31b3cd763e414fdc1e0c504027852acc2e0 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp @@ -429,14 +429,14 @@ namespace SimDynamics std::vector<BulletRobot::LinkInfo> links = btRobot->getLinks(); std::vector<DynamicsObjectPtr> nodes = btRobot->getDynamicsRobotNodes(); - for (size_t i = 0; i < nodes.size(); i++) + for (const auto & node : nodes) { - addObject(nodes[i]); + addObject(node); } - for (size_t i = 0; i < links.size(); i++) + for (auto & link : links) { - addLink(links[i]); + addLink(link); } return DynamicsEngine::addRobot(r); @@ -463,19 +463,19 @@ namespace SimDynamics e->updateRobots(timeStep); - for (unsigned int i = 0; i < e->callbacks.size(); i++) + for (auto & callback : e->callbacks) { - e->callbacks[i].first(e->callbacks[i].second, timeStep); + callback.first(callback.second, timeStep); } } void BulletEngine::updateRobots(btScalar timeStep) { - for (size_t i = 0; i < robots.size(); i++) + for (auto & robot : robots) { - robots[i]->actuateJoints(static_cast<double>(timeStep)); - robots[i]->updateSensors(static_cast<double>(timeStep)); + robot->actuateJoints(static_cast<double>(timeStep)); + robot->updateSensors(static_cast<double>(timeStep)); } } @@ -494,14 +494,14 @@ namespace SimDynamics std::vector<DynamicsObjectPtr> nodes = btRobot->getDynamicsRobotNodes(); - for (size_t i = 0; i < links.size(); i++) + for (auto & link : links) { - removeLink(links[i]); + removeLink(link); } - for (size_t i = 0; i < nodes.size(); i++) + for (const auto & node : nodes) { - removeObject(nodes[i]); + removeObject(node); } return DynamicsEngine::removeRobot(r); @@ -516,9 +516,9 @@ namespace SimDynamics dynamicsWorld->addConstraint(l.joint.get(), true); #endif - for (size_t i = 0; i < l.disabledCollisionPairs.size(); i++) + for (auto & disabledCollisionPair : l.disabledCollisionPairs) { - this->disableCollision(static_cast<DynamicsObject*>(l.disabledCollisionPairs[i].first.get()), static_cast<DynamicsObject*>(l.disabledCollisionPairs[i].second.get())); + this->disableCollision(static_cast<DynamicsObject*>(disabledCollisionPair.first.get()), static_cast<DynamicsObject*>(disabledCollisionPair.second.get())); } return true; @@ -714,9 +714,9 @@ namespace SimDynamics std::vector<BulletRobot::LinkInfo> links = br->getLinks(bo); - for (size_t i = 0; i < links.size(); i++) + for (auto & link : links) { - removeLink(links[i]); + removeLink(link); } bool res = br->detachObject(object); @@ -741,9 +741,9 @@ void SimDynamics::BulletEngine::updateAction(btCollisionWorld *collisionWorld, b updateRobots(deltaTimeStep); - for (unsigned int i = 0; i < callbacks.size(); i++) + for (auto & callback : callbacks) { - callbacks[i].first(callbacks[i].second, deltaTimeStep); + callback.first(callback.second, deltaTimeStep); } std::chrono::duration<double> diff = (std::chrono::system_clock::now()-start); // cout << "duration: " << diff.count() << endl; diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp index 0e39b0129367495ce8f9a6c879ce1f8b7f0b6a3c..019669871074a940775af92c3817dc65abfd2f38 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp @@ -75,10 +75,9 @@ namespace SimDynamics robotNodes = robot->getRobotNodes(); - for (size_t i = 0; i < robotNodes.size(); i++) + for (auto rn : robotNodes) { - RobotNodePtr rn = robotNodes[i]; CollisionModelPtr colModel = rn->getCollisionModel(); if (colModel) @@ -174,13 +173,13 @@ namespace SimDynamics BulletObjectPtr drn1 = boost::dynamic_pointer_cast<BulletObject>(dynamicRobotNodes[rn]); VR_ASSERT(drn1); - for (size_t i = 0; i < ic.size(); i++) + for (const auto & i : ic) { - RobotNodePtr rn2 = robot->getRobotNode(ic[i]); + RobotNodePtr rn2 = robot->getRobotNode(i); if (!rn2) { - VR_ERROR << "Error while processing robot node <" << rn->getName() << ">: Ignored collision model <" << ic[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..." << endl; } else { @@ -456,9 +455,9 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (size_t i = 0; i < links.size(); i++) + for (auto & link : links) { - if (links[i].nodeA == node1 && links[i].nodeB == node2) + if (link.nodeA == node1 && link.nodeB == node2) { return true; } @@ -668,9 +667,9 @@ namespace SimDynamics boost::unordered_set<std::string> contactObjectNames; // this seems stupid and it is, but that is abstract interfaces for you. - for (std::vector<SensorPtr>::iterator it = sensors.begin(); it != sensors.end(); it++) + for (auto & sensor : sensors) { - ContactSensorPtr contactSensor = boost::dynamic_pointer_cast<ContactSensor>(*it); + ContactSensorPtr contactSensor = boost::dynamic_pointer_cast<ContactSensor>(sensor); if (contactSensor) { @@ -682,11 +681,8 @@ namespace SimDynamics std::vector<SimDynamics::DynamicsEngine::DynamicsContactInfo> contacts = world->getEngine()->getContacts(); boost::unordered_map<std::string, VirtualRobot::ContactSensor::ContactFrame> frameMap; - for (std::vector<SimDynamics::DynamicsEngine::DynamicsContactInfo>::iterator it = contacts.begin(); - it != contacts.end(); it++) + for (auto & contact : contacts) { - const SimDynamics::DynamicsEngine::DynamicsContactInfo& contact = *it; - if (contact.objectAName.empty() || contact.objectBName.empty()) { continue; @@ -723,9 +719,9 @@ namespace SimDynamics } // Update forces and torques - for (std::vector<SensorPtr>::iterator it = sensors.begin(); it != sensors.end(); it++) + for (auto & sensor : sensors) { - ForceTorqueSensorPtr ftSensor = boost::dynamic_pointer_cast<ForceTorqueSensor>(*it); + ForceTorqueSensorPtr ftSensor = boost::dynamic_pointer_cast<ForceTorqueSensor>(sensor); if (ftSensor) { @@ -741,7 +737,7 @@ namespace SimDynamics } else { - ContactSensorPtr contactSensor = boost::dynamic_pointer_cast<ContactSensor>(*it); + ContactSensorPtr contactSensor = boost::dynamic_pointer_cast<ContactSensor>(sensor); if (contactSensor) { @@ -758,11 +754,11 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (size_t i = 0; i < links.size(); i++) + for (auto & link : links) { - if (links[i].nodeJoint == node /*|| links[i].nodeJoint2 == node*/) + if (link.nodeJoint == node /*|| links[i].nodeJoint2 == node*/) { - return links[i]; + return link; } } @@ -774,11 +770,11 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (size_t i = 0; i < links.size(); i++) + for (auto & link : links) { - if ((links[i].dynNode1 == object1 && links[i].dynNode2 == object2) || (links[i].dynNode1 == object2 && links[i].dynNode2 == object1)) + if ((link.dynNode1 == object1 && link.dynNode2 == object2) || (link.dynNode1 == object2 && link.dynNode2 == object1)) { - return links[i]; + return link; } } @@ -791,11 +787,11 @@ namespace SimDynamics MutexLockPtr lock = getScopedLock(); std::vector<BulletRobot::LinkInfo> result; - for (size_t i = 0; i < links.size(); i++) + for (auto & link : links) { - if (links[i].nodeJoint == node /*|| links[i].nodeJoint2 == node*/ || links[i].nodeA == node || links[i].nodeB == node) + if (link.nodeJoint == node /*|| links[i].nodeJoint2 == node*/ || link.nodeA == node || link.nodeB == node) { - result.push_back(links[i]); + result.push_back(link); } } @@ -807,11 +803,11 @@ namespace SimDynamics MutexLockPtr lock = getScopedLock(); std::vector<BulletRobot::LinkInfo> result; - for (size_t i = 0; i < links.size(); i++) + for (auto & link : links) { - if (links[i].dynNode1 == node || links[i].dynNode2 == node) + if (link.dynNode1 == node || link.dynNode2 == node) { - result.push_back(links[i]); + result.push_back(link); } } @@ -964,9 +960,9 @@ namespace SimDynamics return true; // not a failure, object is not attached } - for (size_t i = 0; i < ls.size(); i++) + for (const auto & l : ls) { - res = res & removeLink(ls[i]); + res = res & removeLink(l); } VR_INFO << "Detached object " << object->getName() << " from robot " << robot->getName() << endl; @@ -977,9 +973,9 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (size_t i = 0; i < links.size(); i++) + for (auto & link : links) { - if (links[i].nodeJoint == node /*|| links[i].nodeJoint2 == node*/) + if (link.nodeJoint == node /*|| links[i].nodeJoint2 == node*/) { return true; } diff --git a/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp b/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp index cc1e72c6c44fc85e06b69419e0a87122aeb2ece7..04b53c60e9b27549af27b358becb1bb2ef2be94c 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/SimoxMotionState.cpp @@ -138,11 +138,11 @@ namespace SimDynamics std::vector<BulletRobot::LinkInfo> links = bdr->getLinks(rn); // update all involved joint values - for (size_t i = 0; i < links.size(); i++) + for (auto & link : links) { - if (links[i].nodeJoint) + if (link.nodeJoint) { - float ja = float(bdr->getJointAngle(links[i].nodeJoint)); + float ja = float(bdr->getJointAngle(link.nodeJoint)); #ifdef _DEBUG if (boost::math::isnan(ja)) @@ -152,7 +152,7 @@ namespace SimDynamics #endif // we can update the joint value via an RobotNodeActuator - RobotNodeActuatorPtr rna(new RobotNodeActuator(links[i].nodeJoint)); + RobotNodeActuatorPtr rna(new RobotNodeActuator(link.nodeJoint)); rna->updateJointAngle(ja); } } diff --git a/SimDynamics/DynamicsEngine/DynamicsEngine.cpp b/SimDynamics/DynamicsEngine/DynamicsEngine.cpp index 917721c3c371c86a1d5a0da88ef08e05108f564c..9318f44d16a2ca8e5a698c3afd6885e55cfb2375 100644 --- a/SimDynamics/DynamicsEngine/DynamicsEngine.cpp +++ b/SimDynamics/DynamicsEngine/DynamicsEngine.cpp @@ -88,9 +88,9 @@ namespace SimDynamics if (find(robots.begin(), robots.end(), r) == robots.end()) { - for (size_t i = 0; i < robots.size(); i++) + for (auto & robot : robots) { - if (robots[i]->getRobot() == r->getRobot()) + if (robot->getRobot() == r->getRobot()) { VR_ERROR << "Only one DynamicsWrapper per robot allowed. Robot " << r->getName() << endl; return false; @@ -332,11 +332,11 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (size_t i = 0; i < objects.size(); i++) + for (auto & object : objects) { - if (objects[i]->getName() == objectName) + if (object->getName() == objectName) { - return objects[i]; + return object; } } @@ -347,9 +347,9 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (size_t i = 0; i < objects.size(); i++) + for (auto & object : objects) { - objects[i]->activate(); + object->activate(); } } @@ -364,11 +364,11 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (size_t i = 0; i < robots.size(); i++) + for (auto & robot : robots) { - if (robots[i]->getRobot() == r) + if (robot->getRobot() == r) { - return robots[i]; + return robot; } } @@ -379,11 +379,11 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (size_t i = 0; i < robots.size(); i++) + for (auto & robot : robots) { - if (robots[i]->getName() == robName) + if (robot->getName() == robName) { - return robots[i]; + return robot; } } diff --git a/SimDynamics/DynamicsEngine/DynamicsRobot.cpp b/SimDynamics/DynamicsEngine/DynamicsRobot.cpp index 1558a3b90cb189e3174468e7d9e280557b3bd439..a8a9aa52e397abfc209d1396ff858efaa13069e7 100644 --- a/SimDynamics/DynamicsEngine/DynamicsRobot.cpp +++ b/SimDynamics/DynamicsEngine/DynamicsRobot.cpp @@ -454,12 +454,12 @@ namespace SimDynamics void DynamicsRobot::enableSelfCollisions(bool enable) { // deactivate all self collisions - for (size_t i = 0; i < robotNodes.size(); i++) + for (const auto & i : robotNodes) { - auto drn1 = getDynamicsRobotNode(robotNodes.at(i)); - for (size_t j = 0; j < robotNodes.size(); j++) + auto drn1 = getDynamicsRobotNode(i); + for (const auto & robotNode : robotNodes) { - auto drn2 = getDynamicsRobotNode(robotNodes.at(j)); + auto drn2 = getDynamicsRobotNode(robotNode); if(enable) DynamicsWorld::GetWorld()->getEngine()->enableCollision(drn1.get(), drn2.get()); else diff --git a/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp b/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp index a79e305f98091a8e647c224c4685ecd5087c8f03..1c61f9ac81839e3beddfbe247bb223a541ec408e 100644 --- a/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp +++ b/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp @@ -236,9 +236,9 @@ void SimDynamicsWindow::buildVisualization() viewer->addVisualization(dynamicsRobot, colModel); viewer->addVisualization(dynamicsObject, colModel); - for (size_t i = 0; i < dynamicsObjects.size(); i++) + for (const auto & dynamicsObject : dynamicsObjects) { - viewer->addVisualization(dynamicsObjects[i], colModel); + viewer->addVisualization(dynamicsObject, colModel); } if (dynamicsObject2) @@ -263,14 +263,14 @@ void SimDynamicsWindow::comVisu() { std::vector<RobotNodePtr> n = robot->getRobotNodes(); - for (size_t i = 0; i < n.size(); i++) + for (const auto & i : n) { SoSeparator* sep = new SoSeparator; comSep->addChild(sep); - Eigen::Matrix4f cp = dynamicsRobot->getComGlobal(n[i]); + Eigen::Matrix4f cp = dynamicsRobot->getComGlobal(i); sep->addChild(CoinVisualizationFactory::getMatrixTransformScaleMM2M(cp)); sep->addChild(CoinVisualizationFactory::CreateCoordSystemVisualization(5.0f)); - comVisuMap[n[i]] = sep; + comVisuMap[i] = sep; } } } @@ -319,12 +319,12 @@ void SimDynamicsWindow::updateJoints() UI.comboBoxRobotNode->clear(); std::vector<RobotNodePtr> nodes = robot->getRobotNodes(); - for (size_t i = 0; i < nodes.size(); i++) + for (auto & node : nodes) { - if (nodes[i]->isRotationalJoint() || nodes[i]->isTranslationalJoint()) + if (node->isRotationalJoint() || node->isTranslationalJoint()) { - robotNodes.push_back(nodes[i]); - QString qstr(nodes[i]->getName().c_str()); + robotNodes.push_back(node); + QString qstr(node->getName().c_str()); UI.comboBoxRobotNode->addItem(qstr); } } @@ -831,17 +831,17 @@ void SimDynamicsWindow::updateContactVisu() std::vector<SimDynamics::DynamicsEngine::DynamicsContactInfo> c = dynamicsWorld->getEngine()->getContacts(); - for (size_t i = 0; i < c.size(); i++) + for (auto & i : c) { - cout << "Contact: " << c[i].objectAName << " + " << c[i].objectBName << endl; + cout << "Contact: " << i.objectAName << " + " << i.objectBName << endl; SoSeparator* normal = new SoSeparator; SoMatrixTransform* m = new SoMatrixTransform; SbMatrix ma; ma.makeIdentity(); - ma.setTranslate(SbVec3f(c[i].posGlobalB(0), c[i].posGlobalB(1), c[i].posGlobalB(2))); + ma.setTranslate(SbVec3f(i.posGlobalB(0), i.posGlobalB(1), i.posGlobalB(2))); m->matrix.setValue(ma); normal->addChild(m); - SoSeparator* n = CoinVisualizationFactory::CreateArrow(c[i].normalGlobalB, 50.0f); + SoSeparator* n = CoinVisualizationFactory::CreateArrow(i.normalGlobalB, 50.0f); if (n) { @@ -851,10 +851,10 @@ void SimDynamicsWindow::updateContactVisu() SoSeparator* normal2 = new SoSeparator; SoMatrixTransform* m2 = new SoMatrixTransform; ma.makeIdentity(); - ma.setTranslate(SbVec3f(c[i].posGlobalA(0), c[i].posGlobalA(1), c[i].posGlobalA(2))); + ma.setTranslate(SbVec3f(i.posGlobalA(0), i.posGlobalA(1), i.posGlobalA(2))); m2->matrix.setValue(ma); normal2->addChild(m2); - SoSeparator* n2 = CoinVisualizationFactory::CreateArrow(-c[i].normalGlobalB, 50.0f); + SoSeparator* n2 = CoinVisualizationFactory::CreateArrow(-i.normalGlobalB, 50.0f); if (n2) { diff --git a/VirtualRobot/BoundingBox.cpp b/VirtualRobot/BoundingBox.cpp index 204855283ecc0231658b4f36f5ed12ca7aa06caa..82277538f8fa0619289ef7b9c59df43d23ccffe5 100644 --- a/VirtualRobot/BoundingBox.cpp +++ b/VirtualRobot/BoundingBox.cpp @@ -147,10 +147,10 @@ namespace VirtualRobot result[7] << max(0), max(1), max(2); Eigen::Matrix4f m; - for (int i = 0; i < 8; i++) + for (const auto & i : result) { m.setIdentity(); - m.block(0, 3, 3, 1) = result[i]; + m.block(0, 3, 3, 1) = i; m = pose * m; result3.push_back(m.block(0, 3, 3, 1)); } diff --git a/VirtualRobot/CollisionDetection/CDManager.cpp b/VirtualRobot/CollisionDetection/CDManager.cpp index bd44df1be45622c376b775331e57e90ae1f14702..cfc22f584a230113fd39375cf44a6a3e6a5d51fb 100644 --- a/VirtualRobot/CollisionDetection/CDManager.cpp +++ b/VirtualRobot/CollisionDetection/CDManager.cpp @@ -39,11 +39,11 @@ namespace VirtualRobot VR_WARNING << "CollisionModel of SceneObjectSet '" << m->getName() << "' is linked to a different instance of collision checker than this CollisionManager..." << endl; } - for (size_t i = 0; i < colModels.size(); i++) + for (const auto & colModel : colModels) { - if (m != colModels[i]) + if (m != colModel) { - addCollisionModelPair(colModels[i], m); + addCollisionModelPair(colModel, m); } } @@ -73,11 +73,11 @@ namespace VirtualRobot } // check all colmodels - for (unsigned int i = 0; i < colModels.size(); i++) + for (const auto & colModel : colModels) { - if (m != colModels[i]) + if (m != colModel) { - if (colChecker->checkCollision(colModels[i], m)) + if (colChecker->checkCollision(colModel, m)) { return true; } @@ -101,11 +101,11 @@ namespace VirtualRobot } // check all colmodels - for (unsigned int i = 0; i < colModels.size(); i++) + for (const auto & colModel : colModels) { - if (m != colModels[i]) + if (m != colModel) { - tmp = (float)colChecker->calculateDistance(colModels[i], m); + tmp = (float)colChecker->calculateDistance(colModel, m); if (tmp < minDist) { @@ -123,9 +123,9 @@ namespace VirtualRobot { float minDist = FLT_MAX; - for (size_t i = 0; i < sets.size(); i++) + for (const auto & set : sets) { - float tmp = (float)colChecker->calculateDistance(m, sets[i]); + float tmp = (float)colChecker->calculateDistance(m, set); if (tmp < minDist) { @@ -172,9 +172,9 @@ namespace VirtualRobot int _trID1; int _trID2; - for (size_t i = 0; i < sets.size(); i++) + for (const auto & set : sets) { - float tmp = (float)colChecker->calculateDistance(m, sets[i], _P1, _P2, &_trID1, &_trID2); + float tmp = (float)colChecker->calculateDistance(m, set, _P1, _P2, &_trID1, &_trID2); if (tmp < minDist) { @@ -247,9 +247,9 @@ namespace VirtualRobot return -1.0f; } - for (unsigned int j = 0; j < colModels.size(); j++) + for (const auto & colModel : colModels) { - tmp = (float)colChecker->calculateDistance(m, colModels[j], _P1, _P2, &_trID1, &_trID2); + tmp = (float)colChecker->calculateDistance(m, colModel, _P1, _P2, &_trID1, &_trID2); if (tmp < minDist) { @@ -272,9 +272,9 @@ namespace VirtualRobot bool CDManager::isInCollision(SceneObjectSetPtr m, std::vector<SceneObjectSetPtr>& sets) { - for (size_t i = 0; i < sets.size(); i++) + for (const auto & set : sets) { - if (colChecker->checkCollision(m, sets[i])) + if (colChecker->checkCollision(m, set)) { return true; } @@ -318,9 +318,9 @@ namespace VirtualRobot bool CDManager::hasSceneObjectSet(SceneObjectSetPtr m) { - for (size_t i = 0; i < colModels.size(); i++) + for (const auto & colModel : colModels) { - if (colModels[i] == m) + if (colModel == m) { return true; } @@ -331,14 +331,14 @@ namespace VirtualRobot bool CDManager::_hasSceneObjectSet(SceneObjectSetPtr m) { - for (size_t i = 0; i < colModels.size(); i++) + for (auto & colModel : colModels) { - if (colModels[i] == m) + if (colModel == m) { return true; } - if (m->getSize() == 1 && colModels[i]->getSize() == 1 && colModels[i]->getSceneObject(0) == m->getSceneObject(0)) + if (m->getSize() == 1 && colModel->getSize() == 1 && colModel->getSceneObject(0) == m->getSceneObject(0)) { return true; } @@ -349,9 +349,9 @@ namespace VirtualRobot bool CDManager::hasSceneObject(SceneObjectPtr m) { - for (size_t i = 0; i < colModels.size(); i++) + for (auto & colModel : colModels) { - if (colModels[i]->getSize() == 1 && colModels[i]->getSceneObject(0) == m) + if (colModel->getSize() == 1 && colModel->getSceneObject(0) == m) { return true; } diff --git a/VirtualRobot/CollisionDetection/CollisionChecker.cpp b/VirtualRobot/CollisionDetection/CollisionChecker.cpp index bab06c9efab07e8db72db7dc8e1cd0495fd10d21..24ca3f860bef47bc31a3b1755fc2c6d9377c91eb 100644 --- a/VirtualRobot/CollisionDetection/CollisionChecker.cpp +++ b/VirtualRobot/CollisionDetection/CollisionChecker.cpp @@ -391,11 +391,11 @@ namespace VirtualRobot SceneObjectSetPtr result(new SceneObjectSet(r->getName(), shared_from_this())); std::vector<RobotNodePtr> cm = r->getRobotNodes(); - for (size_t i = 0; i < cm.size(); i++) + for (auto & i : cm) { - if (cm[i]->getCollisionModel()) + if (i->getCollisionModel()) { - result->addSceneObject(cm[i]); + result->addSceneObject(i); } } @@ -779,13 +779,13 @@ namespace VirtualRobot // bbox was hit, test all points... std::vector< Eigen::Vector3f > pts = colModel->getModelVeticesGlobal(); - for (std::vector< Eigen::Vector3f >::iterator i = pts.begin(); i != pts.end(); i++) + for (auto & pt : pts) { - if (MathTools::getDistancePointPlane(*i, p) <= maxDist) + if (MathTools::getDistancePointPlane(pt, p) <= maxDist) { MathTools::ContactPoint contact; contact.n = p.n; - contact.p = *i; + contact.p = pt; storeContatcs.push_back(contact); } } diff --git a/VirtualRobot/CollisionDetection/CollisionModel.cpp b/VirtualRobot/CollisionDetection/CollisionModel.cpp index 2fc51a4eb80194593a0b1a1501e37a69fff999fe..762d47d4d8ea48450e6eba5b803977a826ac2122 100644 --- a/VirtualRobot/CollisionDetection/CollisionModel.cpp +++ b/VirtualRobot/CollisionDetection/CollisionModel.cpp @@ -219,9 +219,9 @@ namespace VirtualRobot Eigen::Matrix4f t; t.setIdentity(); - for (std::vector<Eigen::Vector3f >::iterator i = model->vertices.begin(); i != model->vertices.end(); i++) + for (auto & vertice : model->vertices) { - t.block(0, 3, 3, 1) = *i; + t.block(0, 3, 3, 1) = vertice; t = globalPose * t; result.push_back(t.block(0, 3, 3, 1)); } @@ -351,16 +351,16 @@ namespace VirtualRobot CollisionCheckerPtr colChecker = colModels[0]->getCollisionChecker(); std::vector<VisualizationNodePtr> visus; - for (size_t i = 0; i < colModels.size(); i++) + for (const auto & colModel : colModels) { - VisualizationNodePtr v = colModels[i]->getVisualization(); + VisualizationNodePtr v = colModel->getVisualization(); if (v) { visus.push_back(v); } - VR_ASSERT(colModels[i]->getCollisionChecker() == colChecker); + VR_ASSERT(colModel->getCollisionChecker() == colChecker); } if (visus.size() == 0) diff --git a/VirtualRobot/Compression/tests/CompressionBZip2Test.cpp b/VirtualRobot/Compression/tests/CompressionBZip2Test.cpp index a97f3a637f5aba7de517c48a70fefd8eda9574d9..09b584e058194f736fd140d9e93030c0443ead06 100644 --- a/VirtualRobot/Compression/tests/CompressionBZip2Test.cpp +++ b/VirtualRobot/Compression/tests/CompressionBZip2Test.cpp @@ -62,9 +62,9 @@ BOOST_AUTO_TEST_CASE(testNullBlock) BOOST_CHECK_EQUAL(ios.eof(), true); - for (int i = 0; i < BLOCK_SIZE_COMPRESSION_TEST; i++) + for (unsigned char i : blockN2) { - BOOST_CHECK_EQUAL(blockN2[i], 0); + BOOST_CHECK_EQUAL(i, 0); } delete bzip2; @@ -95,9 +95,9 @@ BOOST_AUTO_TEST_CASE(testMultipleRandomBlocks) bool ok = false; - for (int j = 0; j < NR_BLOCKS_COMPRESSION_TEST; j++) + for (auto & j : blockN) { - BOOST_CHECK_NO_THROW(ok = bzip2->write((void*)(blockN[j]), BLOCK_SIZE_COMPRESSION_TEST)); + BOOST_CHECK_NO_THROW(ok = bzip2->write((void*)j, BLOCK_SIZE_COMPRESSION_TEST)); BOOST_CHECK_EQUAL(ok, true); } @@ -115,9 +115,9 @@ BOOST_AUTO_TEST_CASE(testMultipleRandomBlocks) ok = false; int nrBytes = 0; - for (int j = 0; j < NR_BLOCKS_COMPRESSION_TEST; j++) + for (auto & j : blockN2) { - BOOST_CHECK_NO_THROW(ok = bzip2b->read((void*)(blockN2[j]), BLOCK_SIZE_COMPRESSION_TEST, nrBytes)); + BOOST_CHECK_NO_THROW(ok = bzip2b->read((void*)j, BLOCK_SIZE_COMPRESSION_TEST, nrBytes)); BOOST_CHECK_EQUAL(ok, true); BOOST_CHECK_EQUAL(nrBytes, BLOCK_SIZE_COMPRESSION_TEST); } @@ -181,9 +181,9 @@ BOOST_AUTO_TEST_CASE(testCorrectEnding) BOOST_CHECK_EQUAL(ok, true); - for (int i = 0; i < sizeSmall; i++) + for (unsigned char i : blockN2) { - BOOST_CHECK_EQUAL(blockN2[i], 0); + BOOST_CHECK_EQUAL(i, 0); } BOOST_CHECK_EQUAL(ios.eof(), false); diff --git a/VirtualRobot/EndEffector/EndEffector.cpp b/VirtualRobot/EndEffector/EndEffector.cpp index 8c2f3ce89e234a16fa9f1042f48fa83ef75a672e..2dfac2961a2d288cae9fa505aa3d889ff4148da3 100644 --- a/VirtualRobot/EndEffector/EndEffector.cpp +++ b/VirtualRobot/EndEffector/EndEffector.cpp @@ -38,9 +38,9 @@ namespace VirtualRobot gcpNode = tcpNode; } - for (size_t i = 0; i < preshapes.size(); i++) + for (const auto & preshape : preshapes) { - registerPreshape(preshapes[i]); + registerPreshape(preshape); } } @@ -180,9 +180,9 @@ namespace VirtualRobot SceneObjectSetPtr cms(new SceneObjectSet(name, colChecker)); cms->addSceneObjects(statics); - for (std::vector<EndEffectorActorPtr>::iterator i = actors.begin(); i != actors.end(); i++) + for (auto & actor : actors) { - cms->addSceneObjects((*i)->getRobotNodes()); + cms->addSceneObjects(actor->getRobotNodes()); } return cms; @@ -260,16 +260,16 @@ namespace VirtualRobot cout << " * Static RobotNodes:" << endl; - for (size_t i = 0; i < statics.size(); i++) + for (auto & i : statics) { - cout << " ** " << statics[i]->getName() << endl; + cout << " ** " << i->getName() << endl; } cout << " * Actors:" << endl; - for (size_t i = 0; i < actors.size(); i++) + for (auto & actor : actors) { - actors[i]->print(); + actor->print(); } cout << endl; @@ -386,11 +386,11 @@ namespace VirtualRobot VirtualRobot::RobotConfigPtr result(new VirtualRobot::RobotConfig(getRobot(), getName())); std::vector< RobotNodePtr > rn = getAllNodes(); - for (size_t i = 0; i < rn.size(); i++) + for (auto & i : rn) { - if (rn[i]->isRotationalJoint() || rn[i]->isTranslationalJoint()) + if (i->isRotationalJoint() || i->isTranslationalJoint()) { - result->setConfig(rn[i]->getName(), rn[i]->getJointValue()); + result->setConfig(i->getName(), i->getJointValue()); } } @@ -415,9 +415,9 @@ namespace VirtualRobot { std::vector< RobotNodePtr > rn = (*iA)->getRobotNodes(); - for (size_t i = 0; i < rn.size(); i++) + for (const auto & i : rn) { - mapR[rn[i]] = rn[i]; + mapR[i] = i; } iA++; @@ -491,9 +491,9 @@ namespace VirtualRobot return false; } - for (size_t j = 0; j < actors.size(); j++) + for (const auto & actor : actors) { - if (!actors[j]->nodesSufficient(nodes)) + if (!actor->nodesSufficient(nodes)) { return false; } @@ -506,9 +506,9 @@ namespace VirtualRobot { float maxActor = 0; - for (size_t j = 0; j < actors.size(); j++) + for (auto & actor : actors) { - float al = actors[j]->getApproximatedLength(); + float al = actor->getApproximatedLength(); if (al > maxActor) { @@ -519,11 +519,11 @@ namespace VirtualRobot BoundingBox bb_all; - for (size_t j = 0; j < statics.size(); j++) + for (auto & j : statics) { - if (statics[j]->getCollisionModel()) + if (j->getCollisionModel()) { - BoundingBox bb = statics[j]->getCollisionModel()->getBoundingBox(); + BoundingBox bb = j->getCollisionModel()->getBoundingBox(); bb_all.addPoint(bb.getMin()); bb_all.addPoint(bb.getMax()); } @@ -608,18 +608,18 @@ namespace VirtualRobot { ss << tt << "<Static>" << endl; - for (size_t i = 0; i < statics.size(); i++) + for (auto & i : statics) { - ss << ttt << "<Node name='" << statics[i]->getName() << "'/>" << endl; + ss << ttt << "<Node name='" << i->getName() << "'/>" << endl; } ss << tt << "</Static>" << endl; } // Actors - for (size_t i = 0; i < actors.size(); i++) + for (auto & actor : actors) { - ss << actors[i]->toXML(ident + 1); + ss << actor->toXML(ident + 1); } ss << pre << "</EndEffector>" << endl; @@ -634,10 +634,8 @@ namespace VirtualRobot int contactCount = 0; - for (size_t i = 0; i < statics.size(); i++) + for (auto n : statics) { - RobotNodePtr n = statics[i]; - if (!n->getCollisionModel()) continue; int id1, id2; diff --git a/VirtualRobot/EndEffector/EndEffectorActor.cpp b/VirtualRobot/EndEffector/EndEffectorActor.cpp index 12f5fc2c12b951e4a305dd5f8bf381cc17097f10..a51a98fc0bbc28440a0f4dc292a39e69e911678f 100644 --- a/VirtualRobot/EndEffector/EndEffectorActor.cpp +++ b/VirtualRobot/EndEffector/EndEffectorActor.cpp @@ -46,12 +46,12 @@ namespace VirtualRobot std::vector<ActorDefinition> newDef; - for (unsigned int i = 0; i < actors.size(); i++) + for (auto & actor : actors) { ActorDefinition a; - a.colMode = actors[i].colMode; - a.directionAndSpeed = actors[i].directionAndSpeed; - a.robotNode = newRobot->getRobotNode(actors[i].robotNode->getName()); + a.colMode = actor.colMode; + a.directionAndSpeed = actor.directionAndSpeed; + a.robotNode = newRobot->getRobotNode(actor.robotNode->getName()); newDef.push_back(a); } @@ -74,13 +74,13 @@ namespace VirtualRobot VR_ASSERT(robot); bool res = true; - for (std::vector<ActorDefinition>::iterator n = actors.begin(); n != actors.end(); n++) + for (auto & actor : actors) { - float v = n->robotNode->getJointValue() + angle * n->directionAndSpeed; + float v = actor.robotNode->getJointValue() + angle * actor.directionAndSpeed; - if (v <= n->robotNode->getJointLimitHi() && v >= n->robotNode->getJointLimitLo()) + if (v <= actor.robotNode->getJointLimitHi() && v >= actor.robotNode->getJointLimitLo()) { - robot->setJointValue(n->robotNode, v); + robot->setJointValue(actor.robotNode, v); //n->robotNode->setJointValue(v); res = false; } @@ -111,16 +111,16 @@ namespace VirtualRobot - for (std::vector<ActorDefinition>::iterator n = actors.begin(); n != actors.end(); n++) + for (auto & actor : actors) { - float oldV = n->robotNode->getJointValue(); - float v = oldV + angle * n->directionAndSpeed; + float oldV = actor.robotNode->getJointValue(); + float v = oldV + angle * actor.directionAndSpeed; - actorStatus[n->robotNode] = eMoving; + actorStatus[actor.robotNode] = eMoving; - if (v <= n->robotNode->getJointLimitHi() && v >= n->robotNode->getJointLimitLo()) + if (v <= actor.robotNode->getJointLimitHi() && v >= actor.robotNode->getJointLimitLo()) { - robot->setJointValue(n->robotNode, v); + robot->setJointValue(actor.robotNode, v); //n->robotNode->setJointValue(v); // check collision @@ -135,10 +135,10 @@ namespace VirtualRobot // actors (don't store contacts) if (!collision) { - for (std::vector<EndEffectorActorPtr>::iterator a = eefActors.begin(); a != eefActors.end(); a++) + for (auto & eefActor : eefActors) { // Don't check for collisions with the actor itself (don't store contacts) - if (((*a)->getName() != name) && isColliding(*a)) //isColliding(eef,*a,newContacts) ) + if ((eefActor->getName() != name) && isColliding(eefActor)) //isColliding(eef,*a,newContacts) ) { collision = true; } @@ -148,9 +148,9 @@ namespace VirtualRobot // static (don't store contacts) if (!collision) { - for (std::vector<RobotNodePtr>::iterator node = eefStatic.begin(); node != eefStatic.end(); node++) + for (auto & node : eefStatic) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(*node); + SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(node); //(don't store contacts) //if( isColliding(eef,so,newContacts,eStatic) ) @@ -169,25 +169,25 @@ namespace VirtualRobot { // reset last position //n->robotNode->setJointValue(oldV); - robot->setJointValue(n->robotNode, oldV); + robot->setJointValue(actor.robotNode, oldV); - actorStatus[n->robotNode] = eCollision; + actorStatus[actor.robotNode] = eCollision; } } else { - actorStatus[n->robotNode] = eFinished; + actorStatus[actor.robotNode] = eFinished; } } // update contacts - for (size_t i = 0; i < newContacts.size(); i++) + for (auto & newContact : newContacts) { // check for double entries (this may happen since we move all actors to the end and may detecting contacts multiple times) bool doubleEntry = false; - for (size_t j = 0; j < storeContacts.size(); j++) + for (auto & storeContact : storeContacts) { - if (storeContacts[j].robotNode == newContacts[i].robotNode && storeContacts[j].obstacle == newContacts[i].obstacle) + if (storeContact.robotNode == newContact.robotNode && storeContact.obstacle == newContact.obstacle) { doubleEntry = true; break; @@ -197,31 +197,31 @@ namespace VirtualRobot if (!doubleEntry) { int id1, id2; - newContacts[i].distance = colChecker->calculateDistance(newContacts[i].robotNode->getCollisionModel(), newContacts[i].obstacle->getCollisionModel(), newContacts[i].contactPointFingerGlobal, newContacts[i].contactPointObstacleGlobal, &id1, &id2); - newContacts[i].contactPointFingerLocal = newContacts[i].obstacle->toLocalCoordinateSystemVec(newContacts[i].contactPointFingerGlobal); - newContacts[i].contactPointObstacleLocal = newContacts[i].obstacle->toLocalCoordinateSystemVec(newContacts[i].contactPointObstacleGlobal); + newContact.distance = colChecker->calculateDistance(newContact.robotNode->getCollisionModel(), newContact.obstacle->getCollisionModel(), newContact.contactPointFingerGlobal, newContact.contactPointObstacleGlobal, &id1, &id2); + newContact.contactPointFingerLocal = newContact.obstacle->toLocalCoordinateSystemVec(newContact.contactPointFingerGlobal); + newContact.contactPointObstacleLocal = newContact.obstacle->toLocalCoordinateSystemVec(newContact.contactPointObstacleGlobal); // compute approach direction // todo: this could be done more elegantly (Jacobian) RobotConfigPtr config = getConfiguration(); - Eigen::Vector3f contGlobal1 = newContacts[i].contactPointFingerGlobal; - Eigen::Vector3f contFinger = newContacts[i].robotNode->toLocalCoordinateSystemVec(contGlobal1); + Eigen::Vector3f contGlobal1 = newContact.contactPointFingerGlobal; + Eigen::Vector3f contFinger = newContact.robotNode->toLocalCoordinateSystemVec(contGlobal1); this->moveActor(angle); - Eigen::Vector3f contGlobal2 = newContacts[i].robotNode->toGlobalCoordinateSystemVec(contFinger); - newContacts[i].approachDirectionGlobal = contGlobal2 - contGlobal1; - newContacts[i].approachDirectionGlobal.normalize(); + Eigen::Vector3f contGlobal2 = newContact.robotNode->toGlobalCoordinateSystemVec(contFinger); + newContact.approachDirectionGlobal = contGlobal2 - contGlobal1; + newContact.approachDirectionGlobal.normalize(); robot->setJointValues(config); - storeContacts.push_back(newContacts[i]); + storeContacts.push_back(newContact); } } // check what we should return bool res = true; - for (std::vector<ActorDefinition>::iterator n = actors.begin(); n != actors.end(); n++) + for (auto & actor : actors) { // if at least one actor is not in collision and not at its joint limits, we are still in the process of closing the fingers - if (actorStatus[n->robotNode] == eMoving) + if (actorStatus[actor.robotNode] == eMoving) res = false; } @@ -235,15 +235,15 @@ namespace VirtualRobot //Eigen::Vector3f contact; bool col = false; - for (std::vector<ActorDefinition>::iterator n = actors.begin(); n != actors.end(); n++) + for (auto & actor : actors) { - for (std::vector<SceneObjectPtr>::iterator o = colModels.begin(); o != colModels.end(); o++) + for (auto & colModel : colModels) { - if ((n->colMode & checkColMode) && - ((*o)->getCollisionModel()) && - n->robotNode->getCollisionModel() && - colChecker->checkCollision(n->robotNode->getCollisionModel(), (*o)->getCollisionModel())) + if ((actor.colMode & checkColMode) && + (colModel->getCollisionModel()) && + actor.robotNode->getCollisionModel() && + colChecker->checkCollision(actor.robotNode->getCollisionModel(), colModel->getCollisionModel())) { col = true; @@ -251,8 +251,8 @@ namespace VirtualRobot EndEffector::ContactInfo ci; ci.eef = eef; ci.actor = shared_from_this(); - ci.robotNode = n->robotNode; - ci.obstacle = *o; + ci.robotNode = actor.robotNode; + ci.obstacle = colModel; // todo: maybe not needed here: we are in collision, distance makes no sense... // later the distance is calculated anyway (with slightly opened actors) @@ -271,9 +271,9 @@ namespace VirtualRobot bool EndEffectorActor::isColliding(SceneObjectSetPtr obstacles, CollisionMode checkColMode) { - for (std::vector<ActorDefinition>::iterator n = actors.begin(); n != actors.end(); n++) + for (auto & actor : actors) { - if ((n->colMode & checkColMode) && n->robotNode->getCollisionModel() && colChecker->checkCollision(n->robotNode->getCollisionModel(), obstacles)) + if ((actor.colMode & checkColMode) && actor.robotNode->getCollisionModel() && colChecker->checkCollision(actor.robotNode->getCollisionModel(), obstacles)) { return true; } @@ -289,9 +289,9 @@ namespace VirtualRobot return false; } - for (std::vector<ActorDefinition>::iterator n = actors.begin(); n != actors.end(); n++) + for (auto & actor : actors) { - if ((n->colMode & checkColMode) && n->robotNode->getCollisionModel() && colChecker->checkCollision(n->robotNode->getCollisionModel(), obstacle->getCollisionModel())) + if ((actor.colMode & checkColMode) && actor.robotNode->getCollisionModel() && colChecker->checkCollision(actor.robotNode->getCollisionModel(), obstacle->getCollisionModel())) { return true; } @@ -302,11 +302,11 @@ namespace VirtualRobot bool EndEffectorActor::isColliding(EndEffectorActorPtr obstacle) { - for (std::vector<ActorDefinition>::iterator n = actors.begin(); n != actors.end(); n++) + for (auto & actor : actors) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(n->robotNode); + SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(actor.robotNode); - if ((n->colMode & eActors) && obstacle->isColliding(so)) + if ((actor.colMode & eActors) && obstacle->isColliding(so)) { return true; } @@ -323,18 +323,18 @@ namespace VirtualRobot std::vector<RobotNodePtr> obstacleStatics; obstacle->getStatics(obstacleStatics); - for (std::vector<EndEffectorActorPtr>::iterator actor = obstacleActors.begin(); actor != obstacleActors.end(); actor++) + for (auto & obstacleActor : obstacleActors) { // Don't check for collisions with the actor itself - if (((*actor)->getName() != name) && isColliding(*actor)) + if ((obstacleActor->getName() != name) && isColliding(obstacleActor)) { return true; } } - for (std::vector<RobotNodePtr>::iterator node = obstacleStatics.begin(); node != obstacleStatics.end(); node++) + for (auto & obstacleStatic : obstacleStatics) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(*node); + SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(obstacleStatic); if (isColliding(so, EndEffectorActor::eStatic)) { @@ -353,18 +353,18 @@ namespace VirtualRobot std::vector<RobotNodePtr> obstacleStatics; obstacle->getStatics(obstacleStatics); - for (std::vector<EndEffectorActorPtr>::iterator actor = obstacleActors.begin(); actor != obstacleActors.end(); actor++) + for (auto & obstacleActor : obstacleActors) { // Don't check for collisions with the actor itself - if (((*actor)->getName() != name) && isColliding(eef, *actor, storeContacts)) + if ((obstacleActor->getName() != name) && isColliding(eef, obstacleActor, storeContacts)) { return true; } } - for (std::vector<RobotNodePtr>::iterator node = obstacleStatics.begin(); node != obstacleStatics.end(); node++) + for (auto & obstacleStatic : obstacleStatics) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(*node); + SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(obstacleStatic); if (isColliding(eef, so, storeContacts, EndEffectorActor::eStatic)) { @@ -377,11 +377,11 @@ namespace VirtualRobot bool EndEffectorActor::isColliding(EndEffectorPtr eef, EndEffectorActorPtr obstacle, EndEffector::ContactInfoVector& storeContacts) { - for (std::vector<ActorDefinition>::iterator n = actors.begin(); n != actors.end(); n++) + for (auto & actor : actors) { - SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(n->robotNode); + SceneObjectPtr so = boost::dynamic_pointer_cast<SceneObject>(actor.robotNode); - if ((n->colMode & eActors) && obstacle->isColliding(eef, so, storeContacts)) + if ((actor.colMode & eActors) && obstacle->isColliding(eef, so, storeContacts)) { return true; } @@ -401,19 +401,19 @@ namespace VirtualRobot //Eigen::Vector3f contact; bool col = false; - for (std::vector<ActorDefinition>::iterator n = actors.begin(); n != actors.end(); n++) + for (auto & actor : actors) { - if ((n->colMode & checkColMode) && - n->robotNode->getCollisionModel() && - colChecker->checkCollision(n->robotNode->getCollisionModel(), obstacle->getCollisionModel())) + if ((actor.colMode & checkColMode) && + actor.robotNode->getCollisionModel() && + colChecker->checkCollision(actor.robotNode->getCollisionModel(), obstacle->getCollisionModel())) { col = true; // create contact info EndEffector::ContactInfo ci; ci.eef = eef; ci.actor = shared_from_this(); - ci.robotNode = n->robotNode; + ci.robotNode = actor.robotNode; ci.obstacle = obstacle; // todo: not needed here, later we calculate the distance with opened actors... @@ -438,9 +438,9 @@ namespace VirtualRobot { std::vector< RobotNodePtr > res; - for (std::vector<ActorDefinition>::iterator n = actors.begin(); n != actors.end(); n++) + for (auto & actor : actors) { - res.push_back(n->robotNode); + res.push_back(actor.robotNode); } return res; @@ -451,9 +451,9 @@ namespace VirtualRobot cout << " ****" << endl; cout << " ** Name:" << name << endl; - for (size_t i = 0; i < actors.size(); i++) + for (auto & actor : actors) { - cout << " *** RobotNode: " << actors[i].robotNode->getName() << ", Direction/Speed:" << actors[i].directionAndSpeed << endl; + cout << " *** RobotNode: " << actor.robotNode->getName() << ", Direction/Speed:" << actor.directionAndSpeed << endl; //actors[i].robotNode->print(); } @@ -512,11 +512,11 @@ namespace VirtualRobot { BoundingBox bb_all; - for (size_t j = 0; j < actors.size(); j++) + for (auto & actor : actors) { - if (actors[j].robotNode->getCollisionModel()) + if (actor.robotNode->getCollisionModel()) { - BoundingBox bb = actors[j].robotNode->getCollisionModel()->getBoundingBox(); + BoundingBox bb = actor.robotNode->getCollisionModel()->getBoundingBox(); bb_all.addPoint(bb.getMin()); bb_all.addPoint(bb.getMax()); } @@ -535,11 +535,11 @@ namespace VirtualRobot std::vector< RobotConfig::Configuration > c; - for (size_t i = 0; i < actors.size(); i++) + for (auto & actor : actors) { RobotConfig::Configuration e; - e.name = actors[i].robotNode->getName(); - e.value = actors[i].robotNode->getJointValue(); + e.name = actor.robotNode->getName(); + e.value = actor.robotNode->getJointValue(); c.push_back(e); } @@ -562,33 +562,33 @@ namespace VirtualRobot std::string ttt = tt + t; ss << pre << "<Actor name='" << name << "'>" << endl; - for (size_t i = 0; i < actors.size(); i++) + for (auto & actor : actors) { - ss << tt << "<Node name='" << actors[i].robotNode->getName() << "' "; + ss << tt << "<Node name='" << actor.robotNode->getName() << "' "; - if (actors[i].colMode == eNone) + if (actor.colMode == eNone) { ss << "ConsiderCollisions='None' "; } - if (actors[i].colMode == eAll) + if (actor.colMode == eAll) { ss << "ConsiderCollisions='All' "; } else { - if (actors[i].colMode & eActors) + if (actor.colMode & eActors) { ss << "ConsiderCollisions='Actors' "; } - if (actors[i].colMode & eStatic) + if (actor.colMode & eStatic) { ss << "ConsiderCollisions='Static' "; } } - ss << "Direction='" << actors[i].directionAndSpeed << "'/>" << endl; + ss << "Direction='" << actor.directionAndSpeed << "'/>" << endl; } ss << pre << "</Actor>" << endl; diff --git a/VirtualRobot/Grasping/BasicGraspQualityMeasure.cpp b/VirtualRobot/Grasping/BasicGraspQualityMeasure.cpp index 5c2a130b8d65cea9ee39400c713a63eb8c96a676..fb24cba436df699aae87bd44f86ca0718c456527 100644 --- a/VirtualRobot/Grasping/BasicGraspQualityMeasure.cpp +++ b/VirtualRobot/Grasping/BasicGraspQualityMeasure.cpp @@ -147,10 +147,10 @@ namespace VirtualRobot return p; } - for (int i = 0; i < (int)contactPoints.size(); i++) + for (auto & contactPoint : contactPoints) { - p.p += contactPoints[i].p; - p.n += contactPoints[i].n; + p.p += contactPoint.p; + p.n += contactPoint.n; } diff --git a/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp b/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp index 939768f4821383a21706a4f7ada93e3546b75c00..a6fb2f7953086178dcf1e39a1a259798489afaab 100644 --- a/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp +++ b/VirtualRobot/Grasping/GraspEditor/GraspEditorWindow.cpp @@ -595,9 +595,9 @@ namespace VirtualRobot { UI->comboBoxEEF->clear(); - for (size_t i = 0; i < eefs.size(); i++) + for (auto & eef : eefs) { - UI->comboBoxEEF->addItem(QString(eefs[i]->getName().c_str())); + UI->comboBoxEEF->addItem(QString(eef->getName().c_str())); } } diff --git a/VirtualRobot/Grasping/GraspSet.cpp b/VirtualRobot/Grasping/GraspSet.cpp index 1703d6fae37f27dd3c9b7b39899aaf726ead7fe9..8c9ec2b73c044157dd7550ccf7e810ca7ebfdc87 100644 --- a/VirtualRobot/Grasping/GraspSet.cpp +++ b/VirtualRobot/Grasping/GraspSet.cpp @@ -35,8 +35,8 @@ namespace VirtualRobot { VR_ASSERT_MESSAGE(grasp, "NULL grasp"); - for (size_t i = 0; i < grasps.size(); i++) - if (grasps[i] == grasp) + for (const auto & i : grasps) + if (i == grasp) { return true; } @@ -46,9 +46,9 @@ namespace VirtualRobot bool GraspSet::hasGrasp(const std::string& name) { - for (size_t i = 0; i < grasps.size(); i++) + for (auto & grasp : grasps) { - if (grasps[i]->getName() == name) + if (grasp->getName() == name) { return true; } @@ -67,11 +67,11 @@ namespace VirtualRobot { std::vector<GraspPtr> includedGrasp=grasps->getGrasps(); - for(size_t i=0;i<includedGrasp.size();i++) + for(const auto & i : includedGrasp) { - if(!hasGrasp(includedGrasp.at(i))) + if(!hasGrasp(i)) { - addGrasp(includedGrasp.at(i)); + addGrasp(i); } } } @@ -125,11 +125,11 @@ namespace VirtualRobot VirtualRobot::GraspPtr GraspSet::getGrasp(const std::string& name) { - for (size_t i = 0; i < grasps.size(); i++) + for (auto & grasp : grasps) { - if (grasps[i]->getName() == name) + if (grasp->getName() == name) { - return grasps[i]; + return grasp; } } @@ -164,9 +164,9 @@ namespace VirtualRobot ss << t << "<GraspSet name='" << name << "' RobotType='" << robotType << "' EndEffector='" << eef << "'>\n"; - for (size_t i = 0; i < grasps.size(); i++) + for (auto & grasp : grasps) { - ss << grasps[i]->toXML(tabs + 1); + ss << grasp->toXML(tabs + 1); } ss << t << "</GraspSet>\n"; @@ -180,9 +180,9 @@ namespace VirtualRobot GraspSetPtr res(new GraspSet(name, robotType, eef)); // clone grasps - for (std::vector< GraspPtr >::iterator i = grasps.begin(); i != grasps.end(); i++) + for (auto & grasp : grasps) { - res->addGrasp((*i)->clone()); + res->addGrasp(grasp->clone()); } return res; @@ -219,9 +219,9 @@ namespace VirtualRobot { std::vector< GraspPtr > res; - for (size_t i = 0; i < grasps.size(); i++) + for (const auto & grasp : grasps) { - res.push_back(grasps[i]); + res.push_back(grasp); } return res; @@ -229,9 +229,9 @@ namespace VirtualRobot void GraspSet::setPreshape(const std::string& preshape) { - for (size_t i = 0; i < grasps.size(); i++) + for (auto & grasp : grasps) { - grasps[i]->setPreshape(preshape); + grasp->setPreshape(preshape); } } diff --git a/VirtualRobot/IK/AdvancedIKSolver.cpp b/VirtualRobot/IK/AdvancedIKSolver.cpp index 6584353290072bd32494e321cfa51d4a26e9761a..a91953ec03263f10fe633c2034e3286247de97e0 100644 --- a/VirtualRobot/IK/AdvancedIKSolver.cpp +++ b/VirtualRobot/IK/AdvancedIKSolver.cpp @@ -107,9 +107,9 @@ namespace VirtualRobot robot->getEndEffectors(eefs); EndEffectorPtr eef; - for (size_t i = 0; i < eefs.size(); i++) + for (auto & i : eefs) { - if (eefs[i]->getTcp() == rns->getTCP()) + if (i->getTcp() == rns->getTCP()) { if (eef) { @@ -117,7 +117,7 @@ namespace VirtualRobot } else { - eef = eefs[i]; + eef = i; } } } diff --git a/VirtualRobot/IK/CoMIK.cpp b/VirtualRobot/IK/CoMIK.cpp index 49007581c3b341b5ce6f941a2426a3f21e427dd4..46323ec3ec2506f800df240f91e51fa562dddd97 100644 --- a/VirtualRobot/IK/CoMIK.cpp +++ b/VirtualRobot/IK/CoMIK.cpp @@ -22,14 +22,14 @@ namespace VirtualRobot bodyNodes = rnsBodies->getAllRobotNodes(); - for (size_t i = 0; i < bodyNodes.size(); i++) + for (auto & bodyNode : bodyNodes) { // get all joints that influence the body - std::vector<RobotNodePtr> parentsN = bodyNodes[i]->getAllParents(rns); + std::vector<RobotNodePtr> parentsN = bodyNode->getAllParents(rns); // maybe this node is joint and body - if (rnsJoints->hasRobotNode(bodyNodes[i])) - parentsN.push_back(bodyNodes[i]); - bodyNodeParents[bodyNodes[i]] = parentsN; + if (rnsJoints->hasRobotNode(bodyNode)) + parentsN.push_back(bodyNode); + bodyNodeParents[bodyNode] = parentsN; } if (rnsBodies->getMass() == 0) diff --git a/VirtualRobot/IK/DifferentialIK.cpp b/VirtualRobot/IK/DifferentialIK.cpp index 2558d30308189d48549d4f25ca1884d9e0a66a6a..1e0961d8b1a43d2f95a0206f8e59154c5708c482 100644 --- a/VirtualRobot/IK/DifferentialIK.cpp +++ b/VirtualRobot/IK/DifferentialIK.cpp @@ -30,11 +30,11 @@ namespace VirtualRobot checkImprovement = false; nodes = rns->getAllRobotNodes(); - for (size_t i = 0; i < nodes.size(); i++) + for (auto & node : nodes) { - std::vector<RobotNodePtr> p = nodes[i]->getAllParents(rns); - p.push_back(nodes[i]);// if the tcp is not fixed, it must be considered for calculating the Jacobian - parents[nodes[i]] = p; + std::vector<RobotNodePtr> p = node->getAllParents(rns); + p.push_back(node);// if the tcp is not fixed, it must be considered for calculating the Jacobian + parents[node] = p; } convertMMtoM = false; @@ -122,10 +122,8 @@ namespace VirtualRobot size_t index = 0; - for (size_t i = 0; i < tcp_set.size(); i++) + for (auto tcp : tcp_set) { - SceneObjectPtr tcp = tcp_set[i]; - if (this->targets.find(tcp) != this->targets.end()) { auto& mode = this->modes[tcp]; @@ -186,10 +184,8 @@ namespace VirtualRobot // compute error size_t index = 0; - for (size_t i = 0; i < tcp_set.size(); i++) + for (auto tcp : tcp_set) { - SceneObjectPtr tcp = tcp_set[i]; - if (this->targets.find(tcp) != this->targets.end()) { //Eigen::VectorXf delta = @@ -553,9 +549,8 @@ namespace VirtualRobot partJacobians.clear(); - for (size_t i = 0; i < tcp_set.size(); i++) + for (auto tcp : tcp_set) { - SceneObjectPtr tcp = tcp_set[i]; int partSize = 0; if (this->modes[tcp] & IKSolver::X) @@ -613,9 +608,8 @@ namespace VirtualRobot cout << "TCPs:" << endl; - for (size_t t = 0; t < tcp_set.size(); t++) + for (auto tcp : tcp_set) { - SceneObjectPtr tcp = tcp_set[t]; RobotNodePtr tcpRN = boost::dynamic_pointer_cast<RobotNode>(tcp); if (!tcpRN) @@ -830,9 +824,8 @@ namespace VirtualRobot float res = 0; - for (size_t i = 0; i < tcp_set.size(); i++) + for (auto tcp : tcp_set) { - SceneObjectPtr tcp = tcp_set[i]; res += getErrorPosition(tcp); } @@ -844,9 +837,8 @@ namespace VirtualRobot { bool result = true; - for (size_t i = 0; i < tcp_set.size(); i++) + for (auto tcp : tcp_set) { - SceneObjectPtr tcp = tcp_set[i]; float currentErrorPos = getErrorPosition(tcp); float maxErrorPos = tolerancePosition[tcp]; float currentErrorRot = getErrorRotation(tcp); diff --git a/VirtualRobot/IK/HierarchicalIKSolver.cpp b/VirtualRobot/IK/HierarchicalIKSolver.cpp index 8cf7ea9b87baef9f92052815757032957eea24d9..3dfec0767983e71f1f7a8934ee00b901a1a1f1dd 100644 --- a/VirtualRobot/IK/HierarchicalIKSolver.cpp +++ b/VirtualRobot/IK/HierarchicalIKSolver.cpp @@ -61,9 +61,9 @@ bool HierarchicalIKSolver::computeSteps(float stepSize, float minChange, int max bool HierarchicalIKSolver::checkTolerances() { - for (size_t i = 0; i < jacobies.size(); i++) + for (auto & jacobie : jacobies) { - if (!jacobies[i]->checkTolerances()) + if (!jacobie->checkTolerances()) { return false; } diff --git a/VirtualRobot/IK/StackedIK.cpp b/VirtualRobot/IK/StackedIK.cpp index 992f0ca96d3a3930ac1489db726a1765f86fd646..1330b50b2e47be5cf2240492f1d4a18e2614db80 100644 --- a/VirtualRobot/IK/StackedIK.cpp +++ b/VirtualRobot/IK/StackedIK.cpp @@ -71,11 +71,11 @@ namespace VirtualRobot int current_row = 0; - for (size_t i = 0; i < jacDefs.size(); i++) + for (const auto & jacDef : jacDefs) { - Eigen::MatrixXf J = jacDefs[i]->getJacobianMatrix(); + Eigen::MatrixXf J = jacDef->getJacobianMatrix(); jacobian.block(current_row, 0, J.rows(), J.cols()) = J; - error.block(current_row, 0, J.rows(), 1) = jacDefs[i]->getError(); + error.block(current_row, 0, J.rows(), 1) = jacDef->getError(); current_row += J.rows(); } diff --git a/VirtualRobot/IK/SupportPolygon.cpp b/VirtualRobot/IK/SupportPolygon.cpp index b0ae8a139b4973fbcd113c0aa7985448f0d3c766..c47b57536d8ae63f942433d053a52600ba25b1b4 100644 --- a/VirtualRobot/IK/SupportPolygon.cpp +++ b/VirtualRobot/IK/SupportPolygon.cpp @@ -38,10 +38,10 @@ namespace VirtualRobot currentContactPoints2D.clear(); - for (size_t u = 0; u < points.size(); u++) + for (auto & point : points) { - Eigen::Vector2f pt2d = MathTools::projectPointToPlane2D(points[u].p, floor); + Eigen::Vector2f pt2d = MathTools::projectPointToPlane2D(point.p, floor); currentContactPoints2D.push_back(pt2d); } currentContactPoints2D = MathTools::sortPoints(currentContactPoints2D); diff --git a/VirtualRobot/Import/COLLADA-light/pugixml/pugixml.cpp b/VirtualRobot/Import/COLLADA-light/pugixml/pugixml.cpp index b7c4803c4400a97c3da085d0f073081e2b15df09..941f2b0a70968a4fba855d0c8e99ecbc8b4aaba4 100644 --- a/VirtualRobot/Import/COLLADA-light/pugixml/pugixml.cpp +++ b/VirtualRobot/Import/COLLADA-light/pugixml/pugixml.cpp @@ -9277,12 +9277,12 @@ PUGI__NS_BEGIN xpath_node_set_raw ls = lhs->eval_node_set(c, stack, nodeset_eval_all); xpath_node_set_raw rs = rhs->eval_node_set(c, stack, nodeset_eval_all); - for (const xpath_node* li = ls.begin(); li != ls.end(); ++li) - for (const xpath_node* ri = rs.begin(); ri != rs.end(); ++ri) + for (auto l : ls) + for (auto r : rs) { xpath_allocator_capture cri(stack.result); - if (comp(string_value(*li, stack.result), string_value(*ri, stack.result))) + if (comp(string_value(l, stack.result), string_value(r, stack.result))) return true; } @@ -9305,11 +9305,11 @@ PUGI__NS_BEGIN double l = lhs->eval_number(c, stack); xpath_node_set_raw rs = rhs->eval_node_set(c, stack, nodeset_eval_all); - for (const xpath_node* ri = rs.begin(); ri != rs.end(); ++ri) + for (auto r : rs) { xpath_allocator_capture cri(stack.result); - if (comp(l, convert_string_to_number(string_value(*ri, stack.result).c_str()))) + if (comp(l, convert_string_to_number(string_value(r, stack.result).c_str()))) return true; } @@ -9322,11 +9322,11 @@ PUGI__NS_BEGIN xpath_string l = lhs->eval_string(c, stack); xpath_node_set_raw rs = rhs->eval_node_set(c, stack, nodeset_eval_all); - for (const xpath_node* ri = rs.begin(); ri != rs.end(); ++ri) + for (auto r : rs) { xpath_allocator_capture cri(stack.result); - if (comp(l, string_value(*ri, stack.result))) + if (comp(l, string_value(r, stack.result))) return true; } @@ -9356,17 +9356,17 @@ PUGI__NS_BEGIN xpath_node_set_raw ls = lhs->eval_node_set(c, stack, nodeset_eval_all); xpath_node_set_raw rs = rhs->eval_node_set(c, stack, nodeset_eval_all); - for (const xpath_node* li = ls.begin(); li != ls.end(); ++li) + for (auto li : ls) { xpath_allocator_capture cri(stack.result); - double l = convert_string_to_number(string_value(*li, stack.result).c_str()); + double l = convert_string_to_number(string_value(li, stack.result).c_str()); - for (const xpath_node* ri = rs.begin(); ri != rs.end(); ++ri) + for (auto r : rs) { xpath_allocator_capture crii(stack.result); - if (comp(l, convert_string_to_number(string_value(*ri, stack.result).c_str()))) + if (comp(l, convert_string_to_number(string_value(r, stack.result).c_str()))) return true; } } @@ -9380,11 +9380,11 @@ PUGI__NS_BEGIN double l = lhs->eval_number(c, stack); xpath_node_set_raw rs = rhs->eval_node_set(c, stack, nodeset_eval_all); - for (const xpath_node* ri = rs.begin(); ri != rs.end(); ++ri) + for (auto r : rs) { xpath_allocator_capture cri(stack.result); - if (comp(l, convert_string_to_number(string_value(*ri, stack.result).c_str()))) + if (comp(l, convert_string_to_number(string_value(r, stack.result).c_str()))) return true; } @@ -9397,11 +9397,11 @@ PUGI__NS_BEGIN xpath_node_set_raw ls = lhs->eval_node_set(c, stack, nodeset_eval_all); double r = rhs->eval_number(c, stack); - for (const xpath_node* li = ls.begin(); li != ls.end(); ++li) + for (auto l : ls) { xpath_allocator_capture cri(stack.result); - if (comp(convert_string_to_number(string_value(*li, stack.result).c_str()), r)) + if (comp(convert_string_to_number(string_value(l, stack.result).c_str()), r)) return true; } @@ -9939,14 +9939,14 @@ PUGI__NS_BEGIN // self axis preserves the original order if (axis == axis_self) ns.set_type(s.type()); - for (const xpath_node* it = s.begin(); it != s.end(); ++it) + for (auto it : s) { size_t size = ns.size(); // in general, all axes generate elements in a particular order, but there is no order guarantee if axis is applied to two nodes if (axis != axis_self && size != 0) ns.set_type(xpath_node_set::type_unsorted); - step_fill(ns, *it, stack.result, once, v); + step_fill(ns, it, stack.result, once, v); if (_right) apply_predicates(ns, size, stack, eval); } } @@ -10222,11 +10222,11 @@ PUGI__NS_BEGIN xpath_node_set_raw ns = _left->eval_node_set(c, stack, nodeset_eval_all); - for (const xpath_node* it = ns.begin(); it != ns.end(); ++it) + for (auto n : ns) { xpath_allocator_capture cri(stack.result); - r += convert_string_to_number(string_value(*it, stack.result).c_str()); + r += convert_string_to_number(string_value(n, stack.result).c_str()); } return r; @@ -12059,20 +12059,20 @@ namespace pugi PUGI__FN xpath_variable_set::xpath_variable_set() { - for (size_t i = 0; i < sizeof(_data) / sizeof(_data[0]); ++i) - _data[i] = 0; + for (auto & i : _data) + i = 0; } PUGI__FN xpath_variable_set::~xpath_variable_set() { - for (size_t i = 0; i < sizeof(_data) / sizeof(_data[0]); ++i) - _destroy(_data[i]); + for (auto & i : _data) + _destroy(i); } PUGI__FN xpath_variable_set::xpath_variable_set(const xpath_variable_set& rhs) { - for (size_t i = 0; i < sizeof(_data) / sizeof(_data[0]); ++i) - _data[i] = 0; + for (auto & i : _data) + i = 0; _assign(rhs); } diff --git a/VirtualRobot/ManipulationObject.cpp b/VirtualRobot/ManipulationObject.cpp index 6792536ada5526d2c06cf0fe7b9764a4179a0368..dc25836f055f8dd54c2b5e1cdf31d731c300c260 100644 --- a/VirtualRobot/ManipulationObject.cpp +++ b/VirtualRobot/ManipulationObject.cpp @@ -71,8 +71,8 @@ namespace VirtualRobot { VR_ASSERT_MESSAGE(graspSet, "NULL data"); - for (size_t i = 0; i < graspSets.size(); i++) - if (graspSets[i] == graspSet) + for (const auto & i : graspSets) + if (i == graspSet) { return true; } @@ -82,8 +82,8 @@ namespace VirtualRobot bool ManipulationObject::hasGraspSet(const std::string& robotType, const std::string& eef) { - for (size_t i = 0; i < graspSets.size(); i++) - if (graspSets[i]->getRobotType() == robotType && graspSets[i]->getEndEffector() == eef) + for (auto & graspSet : graspSets) + if (graspSet->getRobotType() == robotType && graspSet->getEndEffector() == eef) { return true; } @@ -102,10 +102,10 @@ namespace VirtualRobot VirtualRobot::GraspSetPtr ManipulationObject::getGraspSet(const std::string& robotType, const std::string& eefName) { - for (size_t i = 0; i < graspSets.size(); i++) - if (graspSets[i]->getRobotType() == robotType && graspSets[i]->getEndEffector() == eefName) + for (auto & graspSet : graspSets) + if (graspSet->getRobotType() == robotType && graspSet->getEndEffector() == eefName) { - return graspSets[i]; + return graspSet; } return GraspSetPtr(); @@ -113,10 +113,10 @@ namespace VirtualRobot VirtualRobot::GraspSetPtr ManipulationObject::getGraspSet(const std::string& name) { - for (size_t i = 0; i < graspSets.size(); i++) - if (graspSets[i]->getName() == name) + for (auto & graspSet : graspSets) + if (graspSet->getName() == name) { - return graspSets[i]; + return graspSet; } return GraspSetPtr(); @@ -166,9 +166,9 @@ namespace VirtualRobot ss << getSceneObjectXMLString(basePath, tabs + 1); - for (size_t i = 0; i < graspSets.size(); i++) + for (auto & graspSet : graspSets) { - ss << graspSets[i]->getXMLString(tabs + 1) << "\n"; + ss << graspSet->getXMLString(tabs + 1) << "\n"; } } @@ -208,9 +208,9 @@ namespace VirtualRobot result->setGlobalPose(getGlobalPose()); - for (size_t i = 0; i < graspSets.size(); i++) + for (const auto & graspSet : graspSets) { - result->addGraspSet(graspSets[i]->clone()); + result->addGraspSet(graspSet->clone()); } return result; diff --git a/VirtualRobot/MathTools.cpp b/VirtualRobot/MathTools.cpp index c2e77201448cd5233a35ca1faa403c8cef308c6c..4a9ff054e16fe809747a0b09e850231ae87e5488 100644 --- a/VirtualRobot/MathTools.cpp +++ b/VirtualRobot/MathTools.cpp @@ -943,9 +943,9 @@ namespace VirtualRobot void VIRTUAL_ROBOT_IMPORT_EXPORT MathTools::print(const std::vector<ContactPoint>& points) { - for (size_t i = 0; i < points.size(); i++) + for (const auto & point : points) { - print(points[i]); + print(point); } } @@ -1489,21 +1489,21 @@ namespace VirtualRobot res.x = res.y = res.z = res.w = 0; - for (size_t i = 0; i < quaternions.size(); i++) + for (auto & quaternion : quaternions) { - if (getDot(res, quaternions[i]) > 0) + if (getDot(res, quaternion) > 0) { - res.x += quaternions[i].x; - res.y += quaternions[i].y; - res.z += quaternions[i].z; - res.w += quaternions[i].w; + res.x += quaternion.x; + res.y += quaternion.y; + res.z += quaternion.z; + res.w += quaternion.w; } else { - res.x += -quaternions[i].x; - res.y += -quaternions[i].y; - res.z += -quaternions[i].z; - res.w += -quaternions[i].w; + res.x += -quaternion.x; + res.y += -quaternion.y; + res.z += -quaternion.z; + res.w += -quaternion.w; } } diff --git a/VirtualRobot/Nodes/Sensor.cpp b/VirtualRobot/Nodes/Sensor.cpp index f0af61ac26b4a6b01d9b232af9a6c7756180a39f..9bb817af10d94d271cc3f9ef224bb735f41e2354 100644 --- a/VirtualRobot/Nodes/Sensor.cpp +++ b/VirtualRobot/Nodes/Sensor.cpp @@ -112,9 +112,9 @@ namespace VirtualRobot { std::vector< SceneObjectPtr > children = this->getChildren(); - for (unsigned int i = 0; i < children.size(); i++) + for (auto & i : children) { - children[i]->print(true, true); + i->print(true, true); } } } diff --git a/VirtualRobot/Robot.cpp b/VirtualRobot/Robot.cpp index 857e9fc903ed06f7cf184c79aa14b1ee0c976c2d..2ff32e7afa2f9fd00c62fefdf01f1edcfa5f78bf 100644 --- a/VirtualRobot/Robot.cpp +++ b/VirtualRobot/Robot.cpp @@ -36,9 +36,9 @@ namespace VirtualRobot { std::vector<SceneObjectPtr> c = it->second->getChildren(); - for (size_t j = 0; j < c.size(); j++) + for (const auto & j : c) { - it->second->detachChild(c[j]); + it->second->detachChild(j); } it++; @@ -75,14 +75,14 @@ namespace VirtualRobot std::vector< RobotNodePtr > allNodes; node->collectAllRobotNodes(allNodes); - for (unsigned int i = 0; i < allNodes.size(); i++) + for (auto & allNode : allNodes) { - std::string name = allNodes[i]->getName(); + std::string name = allNode->getName(); if (!this->hasRobotNode(name)) { VR_WARNING << "Robot node with name <" << name << "> was not registered, adding it to RobotNodeMap" << endl; - registerRobotNode(allNodes[i]); + registerRobotNode(allNode); } } } @@ -813,13 +813,13 @@ namespace VirtualRobot std::vector<RobotNodePtr> allNodes; startJoint->collectAllRobotNodes(allNodes); - for (size_t i = 0; i < allNodes.size(); i++) + for (auto & allNode : allNodes) { - RobotNodePtr roN = result->getRobotNode(allNodes[i]->getName()); + RobotNodePtr roN = result->getRobotNode(allNode->getName()); if (roN) { - roN->setJointValueNoUpdate(allNodes[i]->getJointValue()); + roN->setJointValueNoUpdate(allNode->getJointValue()); } } @@ -1043,15 +1043,15 @@ namespace VirtualRobot VirtualRobot::BoundingBox bbox; std::vector<RobotNodePtr> rn = getRobotNodes(); - for (size_t i = 0; i < rn.size(); i++) + for (auto & i : rn) { - if (collisionModel && rn[i]->getCollisionModel()) + if (collisionModel && i->getCollisionModel()) { - bbox.addPoints(rn[i]->getCollisionModel()->getBoundingBox()); + bbox.addPoints(i->getCollisionModel()->getBoundingBox()); } - else if (!collisionModel && rn[i]->getVisualization()) + else if (!collisionModel && i->getVisualization()) { - bbox.addPoints(rn[i]->getVisualization()->getBoundingBox()); + bbox.addPoints(i->getVisualization()->getBoundingBox()); } } @@ -1062,15 +1062,15 @@ namespace VirtualRobot { std::vector<RobotNodePtr> rn = getRobotNodes(); - for (size_t i = 0; i < rn.size(); i++) + for (auto & i : rn) { - std::vector<SensorPtr> sensors = rn[i]->getSensors(); + std::vector<SensorPtr> sensors = i->getSensors(); - for (std::vector<SensorPtr>::iterator it = sensors.begin(); it != sensors.end(); it++) + for (auto & sensor : sensors) { - if ((*it)->getName() == name) + if (sensor->getName() == name) { - return *it; + return sensor; } } } @@ -1083,9 +1083,9 @@ namespace VirtualRobot std::vector<SensorPtr> result; std::vector<RobotNodePtr> rn = getRobotNodes(); - for (size_t i = 0; i < rn.size(); i++) + for (auto & i : rn) { - std::vector<SensorPtr> s = rn[i]->getSensors(); + std::vector<SensorPtr> s = i->getSensors(); if (s.size() > 0) { @@ -1104,9 +1104,9 @@ namespace VirtualRobot ss << "<Robot Type='" << this->type << "' RootNode='" << this->getRootNode()->getName() << "'>" << endl << endl; std::vector<RobotNodePtr> nodes = getRobotNodes(); - for (size_t i = 0; i < nodes.size(); i++) + for (auto & node : nodes) { - ss << nodes[i]->toXML(basePath, modelPath, storeSensors) << endl; + ss << node->toXML(basePath, modelPath, storeSensors) << endl; } ss << endl; @@ -1116,9 +1116,9 @@ namespace VirtualRobot std::vector<RobotNodeSetPtr> rns; this->getRobotNodeSets(rns); - for (size_t i = 0; i < rns.size(); i++) + for (auto & rn : rns) { - ss << rns[i]->toXML(1) << endl; + ss << rn->toXML(1) << endl; } if (rns.size() > 0) @@ -1131,9 +1131,9 @@ namespace VirtualRobot { std::vector<EndEffectorPtr> eefs = this->getEndEffectors(); - for (size_t i = 0; i < eefs.size(); i++) + for (auto & eef : eefs) { - ss << eefs[i]->toXML(1) << endl; + ss << eef->toXML(1) << endl; } if (eefs.size() > 0) diff --git a/VirtualRobot/RobotConfig.cpp b/VirtualRobot/RobotConfig.cpp index 2e32d380219d531c692bb489f1684dabb477ee7c..dd0ce49f7c47af379d4ff5b72c1657a523e2ed92 100644 --- a/VirtualRobot/RobotConfig.cpp +++ b/VirtualRobot/RobotConfig.cpp @@ -20,9 +20,9 @@ namespace VirtualRobot { THROW_VR_EXCEPTION_IF(!robot.lock(), "NULL robot in RobotConfig"); - for (std::vector< Configuration >::const_iterator i = configs.begin(); i != configs.end(); i++) + for (const auto & config : configs) { - setConfig((*i)); + setConfig(config); } } @@ -32,9 +32,9 @@ namespace VirtualRobot { THROW_VR_EXCEPTION_IF(!robot.lock(), "NULL robot in RobotConfig"); - for (std::map< RobotNodePtr, float >::const_iterator i = configs.begin(); i != configs.end(); i++) + for (const auto & config : configs) { - setConfig(i->first, i->second); + setConfig(config.first, config.second); } } @@ -69,9 +69,9 @@ namespace VirtualRobot { cout << " Robot Config <" << name << ">" << endl; - for (std::map< RobotNodePtr, float >::const_iterator i = configs.begin(); i != configs.end(); i++) + for (const auto & config : configs) { - cout << " * " << i->first->getName() << ":\t" << i->second << endl; + cout << " * " << config.first->getName() << ":\t" << config.second << endl; } } @@ -188,9 +188,9 @@ namespace VirtualRobot bool RobotConfig::hasConfig(const std::string& name) const { - for (std::map< RobotNodePtr, float >::const_iterator i = configs.begin(); i != configs.end(); i++) + for (const auto & config : configs) { - if (i->first->getName() == name) + if (config.first->getName() == name) { return true; } diff --git a/VirtualRobot/RobotFactory.cpp b/VirtualRobot/RobotFactory.cpp index 6e2bf1e75a59008f7d1fc883310ad8935bcc9fd9..a0b3bd0dd1e3fd3b4dfc045b1bfee60ad613ce7d 100644 --- a/VirtualRobot/RobotFactory.cpp +++ b/VirtualRobot/RobotFactory.cpp @@ -73,10 +73,8 @@ namespace VirtualRobot std::vector< std::string > childNames = iterC->second; RobotNodePtr node = iterC->first; - for (size_t i = 0; i < childNames.size(); i++) + for (auto childName : childNames) { - std::string childName = childNames[i]; - if (!robot->hasRobotNode(childName)) { THROW_VR_EXCEPTION("Robot " << robot->getName() << ": corrupted RobotNode <" << node->getName() << " child :" << childName << " does not exist..."); @@ -92,11 +90,11 @@ namespace VirtualRobot // register root (performs an initialization of all robot nodes) robot->setRootNode(rootNode); - for (size_t i = 0; i < robotNodes.size(); i++) + for (auto & robotNode : robotNodes) { - if (!robotNodes[i]->getParent() && robotNodes[i] != rootNode) + if (!robotNode->getParent() && robotNode != rootNode) { - VR_ERROR << "RobotNode " << robotNodes[i]->getName() << " is not connected to kinematic structure..." << endl; + VR_ERROR << "RobotNode " << robotNode->getName() << " is not connected to kinematic structure..." << endl; } } @@ -163,11 +161,11 @@ namespace VirtualRobot edges.push_back(edge); } - for (unsigned i = 0; i < children.size(); i++) + for (auto & i : children) { - if (children[i] != currentEdge.first) + if (i != currentEdge.first) { - RobotNodePtr childNode = boost::dynamic_pointer_cast<RobotNode>(children[i]); + RobotNodePtr childNode = boost::dynamic_pointer_cast<RobotNode>(i); // not a robot node if (!childNode) @@ -175,7 +173,7 @@ namespace VirtualRobot continue; } - rnDef.children.push_back(children[i]->getName()); + rnDef.children.push_back(i->getName()); rnDef.invertTransformation.push_back(false); RobotTreeEdge edge; edge.second = childNode; @@ -362,15 +360,15 @@ namespace VirtualRobot std::map<RobotNodePtr, std::vector<SensorPtr> > sensorMap; std::map<RobotNodePtr, bool> directionInversion; - for (size_t i = 0; i < newStructure.parentChildMapping.size(); i++) + for (auto & i : newStructure.parentChildMapping) { - if (!robot->hasRobotNode(newStructure.parentChildMapping[i].name)) + if (!robot->hasRobotNode(i.name)) { - VR_ERROR << "Error in parentChildMapping, no node with name " << newStructure.parentChildMapping[i].name << endl; + VR_ERROR << "Error in parentChildMapping, no node with name " << i.name << endl; return RobotPtr(); } - nodeName = newStructure.parentChildMapping[i].name; + nodeName = i.name; if (newNodes.find(nodeName) == newNodes.end()) { @@ -379,11 +377,11 @@ namespace VirtualRobot newNodes[nodeName] = rn; } - RobotNodePtr parent = newNodes[newStructure.parentChildMapping[i].name]; + RobotNodePtr parent = newNodes[i.name]; - for (size_t j = 0; j < newStructure.parentChildMapping[i].children.size(); j++) + for (size_t j = 0; j < i.children.size(); j++) { - nodeName = newStructure.parentChildMapping[i].children[j]; + nodeName = i.children[j]; if (!robot->hasRobotNode(nodeName)) { @@ -402,7 +400,7 @@ namespace VirtualRobot RobotNodePtr child = newNodes[nodeName]; parent->attachChild(child); - if (newStructure.parentChildMapping[i].invertTransformation[j]) + if (i.invertTransformation[j]) { Eigen::Matrix4f tr = parent->getLocalTransformation().inverse(); localTransformations[child] = tr; @@ -419,9 +417,9 @@ namespace VirtualRobot vf->applyDisplacement(v, tr2); visuMap[parent] = v; - for (size_t pr = 0; pr < v->primitives.size(); pr++) + for (auto & primitive : v->primitives) { - v->primitives[pr]->transform = tr * v->primitives[pr]->transform; + primitive->transform = tr * primitive->transform; } } @@ -437,9 +435,9 @@ namespace VirtualRobot c->setVisualization(v); colMap[parent] = c; - for (size_t pr = 0; pr < v->primitives.size(); pr++) + for (auto & primitive : v->primitives) { - v->primitives[pr]->transform = tr * v->primitives[pr]->transform; + primitive->transform = tr * primitive->transform; } } @@ -545,38 +543,38 @@ namespace VirtualRobot std::vector<RobotNodePtr> nodes = newRobot->getRobotNodes(); - for (size_t i = 0; i < nodes.size(); i++) + for (auto & node : nodes) { - if (visuMap.find(nodes[i]) != visuMap.end()) + if (visuMap.find(node) != visuMap.end()) { - nodes[i]->setVisualization(visuMap[nodes[i]]); + node->setVisualization(visuMap[node]); } else { - nodes[i]->setVisualization(VisualizationNodePtr()); + node->setVisualization(VisualizationNodePtr()); } - if (colMap.find(nodes[i]) != colMap.end()) + if (colMap.find(node) != colMap.end()) { - nodes[i]->setCollisionModel(colMap[nodes[i]]); + node->setCollisionModel(colMap[node]); } else { - nodes[i]->setCollisionModel(CollisionModelPtr()); + node->setCollisionModel(CollisionModelPtr()); } - if (physicsMap.find(nodes[i]) != physicsMap.end()) + if (physicsMap.find(node) != physicsMap.end()) { - nodes[i]->physics = physicsMap[nodes[i]]; + node->physics = physicsMap[node]; } - if (sensorMap.find(nodes[i]) != sensorMap.end()) + if (sensorMap.find(node) != sensorMap.end()) { - auto sensors = sensorMap[nodes[i]]; + auto sensors = sensorMap[node]; for (auto s : sensors) { - nodes[i]->registerSensor(s); + node->registerSensor(s); } } } @@ -607,9 +605,8 @@ namespace VirtualRobot std::vector < SceneObjectPtr > children = nodeA->getChildren(); std::vector<RobotNodePtr> childNodes; - for (size_t i = 0; i < children.size(); i++) + for (auto c : children) { - SceneObjectPtr c = children[i]; RobotNodePtr cRN = boost::dynamic_pointer_cast<RobotNode>(c); if (cRN && cRN != nodeExclude) @@ -626,9 +623,8 @@ namespace VirtualRobot std::vector < SceneObjectPtr > children = nodeA->getChildren(); std::vector<RobotNodePtr> childNodes; - for (size_t i = 0; i < children.size(); i++) + for (auto c : children) { - SceneObjectPtr c = children[i]; SensorPtr cS = boost::dynamic_pointer_cast<Sensor>(c); RobotNodePtr cRN = boost::dynamic_pointer_cast<RobotNode>(c); @@ -709,9 +705,9 @@ namespace VirtualRobot } // attach sensors - for (size_t i = 0; i < sensors.size(); i++) + for (const auto & sensor : sensors) { - SensorPtr s = sensors[i]->clone(newRN); + SensorPtr s = sensor->clone(newRN); } return newRN; @@ -723,19 +719,19 @@ namespace VirtualRobot float kg = 0; - for (size_t i = 0; i < nodes.size(); i++) + for (const auto & node : nodes) { - if (nodes[i]->getVisualization()) + if (node->getVisualization()) { - visus.push_back(nodes[i]->getVisualization()); + visus.push_back(node->getVisualization()); } - if (nodes[i]->getCollisionModel() && nodes[i]->getCollisionModel()->getVisualization()) + if (node->getCollisionModel() && node->getCollisionModel()->getVisualization()) { - colVisus.push_back(nodes[i]->getCollisionModel()->getVisualization()); + colVisus.push_back(node->getCollisionModel()->getVisualization()); } - kg += nodes[i]->getMass(); + kg += node->getMass(); } if (visus.size() > 0) @@ -766,11 +762,11 @@ namespace VirtualRobot newRN->initialize(parentClone); // attach sensors - for (size_t i = 0; i < sensors.size(); i++) + for (const auto & sensor : sensors) { - SensorPtr s = sensors[i]->clone(newRN); + SensorPtr s = sensor->clone(newRN); Eigen::Matrix4f trafoToNewRN = parent?parent->getGlobalPose() * trafo:trafo; - Eigen::Matrix4f t = trafoToNewRN.inverse() * sensors[i]->getGlobalPose(); + Eigen::Matrix4f t = trafoToNewRN.inverse() * sensor->getGlobalPose(); s->setRobotNodeToSensorTransformation(t); } @@ -816,13 +812,12 @@ namespace VirtualRobot std::vector< RobotNodePtr > initialNodes = startNode->getAllParents(); // check for static nodes which are not parent of startNode std::vector< RobotNodePtr > allNodes = robot->getRobotNodes(); - for (size_t i=0;i<allNodes.size();i++) + for (auto rn : allNodes) { - RobotNodePtr rn = allNodes[i]; bool isFixed = true; - for (size_t j = 0; j < nodes.size(); j++) + for (const auto & node : nodes) { - if (rn->hasChild(nodes[j],true)) + if (rn->hasChild(node,true)) { isFixed = false; break; @@ -847,13 +842,12 @@ namespace VirtualRobot // collect sensor nodes std::vector<SensorPtr> childSensorNodes; - for (size_t i = 0; i < initialNodes.size(); i++) + for (auto rn : initialNodes) { - RobotNodePtr rn = initialNodes[i]; std::vector<SceneObjectPtr> c = rn->getChildren(); - for (size_t j = 0; j < c.size(); j++) + for (const auto & j : c) { - SensorPtr s = boost::dynamic_pointer_cast<Sensor>(c[j]); + SensorPtr s = boost::dynamic_pointer_cast<Sensor>(j); if (s) childSensorNodes.push_back(s); } @@ -899,9 +893,9 @@ namespace VirtualRobot if (uniteWithAllChildren.size() == 0) return RobotFactory::clone(robot, robot->getName()); - for (size_t i = 0; i < uniteWithAllChildren.size(); i++) + for (const auto & i : uniteWithAllChildren) { - THROW_VR_EXCEPTION_IF(!robot->hasRobotNode(uniteWithAllChildren[i]), "Could not find RobotNode in robot"); + THROW_VR_EXCEPTION_IF(!robot->hasRobotNode(i), "Could not find RobotNode in robot"); } @@ -916,21 +910,19 @@ namespace VirtualRobot // clone RNS std::vector<RobotNodeSetPtr> rnsets = robot->getRobotNodeSets(); - for (size_t i = 0; i < rnsets.size(); i++) + for (auto rns : rnsets) { - RobotNodeSetPtr rns = rnsets[i]; - bool ok = true; - for (size_t j = 0; j < uniteWithAllChildren.size(); j++) + for (const auto & j : uniteWithAllChildren) { - RobotNodePtr rn = robot->getRobotNode(uniteWithAllChildren[j]); + RobotNodePtr rn = robot->getRobotNode(j); std::vector<RobotNodePtr> allChildren; rn->collectAllRobotNodes(allChildren); - for (size_t k = 0; k < allChildren.size(); k++) + for (auto & k : allChildren) { - if (allChildren[k] == rn) + if (k == rn) continue; - if (rns->hasRobotNode(allChildren[k]->getName())) + if (rns->hasRobotNode(k->getName())) { ok = false; break; @@ -952,11 +944,11 @@ namespace VirtualRobot std::vector<SceneObjectPtr> c = currentNode->getChildren(); - for (size_t i = 0; i < c.size(); i++) + for (auto & i : c) { - if (std::find(uniteWithAllChildren.begin(), uniteWithAllChildren.end(), c[i]->getName()) != uniteWithAllChildren.end()) + if (std::find(uniteWithAllChildren.begin(), uniteWithAllChildren.end(), i->getName()) != uniteWithAllChildren.end()) { - RobotNodePtr currentRN = boost::dynamic_pointer_cast<RobotNode>(c[i]); + RobotNodePtr currentRN = boost::dynamic_pointer_cast<RobotNode>(i); THROW_VR_EXCEPTION_IF(!currentRN, "Only RN allowed in list"); RobotNodePtr currentRNClone = currentRN->clone(robot, false, currentNodeClone); @@ -974,7 +966,7 @@ namespace VirtualRobot } else { - RobotNodePtr currentRN = boost::dynamic_pointer_cast<RobotNode>(c[i]); + RobotNodePtr currentRN = boost::dynamic_pointer_cast<RobotNode>(i); if (currentRN) { RobotNodePtr currentRNClone = currentRN->clone(robot, false, currentNodeClone); @@ -982,12 +974,12 @@ namespace VirtualRobot } else { - SensorPtr s = boost::dynamic_pointer_cast<Sensor>(c[i]); + SensorPtr s = boost::dynamic_pointer_cast<Sensor>(i); if (s) { s->clone(currentNodeClone); } else - VR_INFO << "Skipping node " << c[i]->getName() << endl; + VR_INFO << "Skipping node " << i->getName() << endl; } } diff --git a/VirtualRobot/RobotNodeSet.cpp b/VirtualRobot/RobotNodeSet.cpp index 480a8fac63614838422b18b84d138f85480c9067..dd0384187bc013213d06476a1a4669f002c4d2c8 100644 --- a/VirtualRobot/RobotNodeSet.cpp +++ b/VirtualRobot/RobotNodeSet.cpp @@ -60,15 +60,15 @@ namespace VirtualRobot // now, the objects are stored in the parent's (SceneObjectSet) data structure, so that the methods of SceneObjectSet do work - for (size_t i = 0; i < robotNodes.size(); i++) + for (const auto & robotNode : robotNodes) { - SceneObjectPtr cm = boost::dynamic_pointer_cast<SceneObject>(robotNodes[i]); + SceneObjectPtr cm = boost::dynamic_pointer_cast<SceneObject>(robotNode); if (cm) { if (colChecker != cm->getCollisionChecker()) { - VR_WARNING << "col model of " << robotNodes[i]->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() << endl; } else { @@ -95,10 +95,10 @@ namespace VirtualRobot } else { - for (unsigned int i = 0; i < robotNodeNames.size(); i++) + for (const auto & robotNodeName : robotNodeNames) { - RobotNodePtr node = robot->getRobotNode(robotNodeNames[i]); - THROW_VR_EXCEPTION_IF(!node, "No robot node with name " << robotNodeNames[i] << " found..."); + RobotNodePtr node = robot->getRobotNode(robotNodeName); + THROW_VR_EXCEPTION_IF(!node, "No robot node with name " << robotNodeName << " found..."); robotNodes.push_back(node); } } @@ -249,9 +249,9 @@ namespace VirtualRobot bool RobotNodeSet::hasRobotNode(RobotNodePtr robotNode) const { - for (unsigned int i = 0; i < robotNodes.size(); i++) + for (const auto & i : robotNodes) { - if (robotNodes[i] == robotNode) + if (i == robotNode) { return true; } @@ -261,9 +261,9 @@ namespace VirtualRobot bool RobotNodeSet::hasRobotNode(const std::string &nodeName) const { - for (unsigned int i = 0; i < robotNodes.size(); i++) + for (const auto & robotNode : robotNodes) { - if (robotNodes[i]->getName() == nodeName) + if (robotNode->getName() == nodeName) { return true; } @@ -361,9 +361,9 @@ namespace VirtualRobot { THROW_VR_EXCEPTION_IF(!fillVector, "NULL data"); - for (size_t i = 0; i < robotNodes.size(); i++) + for (const auto & robotNode : robotNodes) { - fillVector->setConfig(robotNodes[i]->getName(), robotNodes[i]->getJointValue()); + fillVector->setConfig(robotNode->getName(), robotNode->getJointValue()); } } @@ -463,11 +463,11 @@ namespace VirtualRobot THROW_VR_EXCEPTION_IF(!rob, "RobotNodeSet::setJointValues: Robot is NULL (The last shared_ptr was deleted)"); WriteLockPtr lock = rob->getWriteLock(); - for (unsigned int i = 0; i < robotNodes.size(); i++) + for (auto & robotNode : robotNodes) { - if (jointValues->hasConfig(robotNodes[i]->getName())) + if (jointValues->hasConfig(robotNode->getName())) { - robotNodes[i]->setJointValueNoUpdate(jointValues->getConfig(robotNodes[i]->getName())); + robotNode->setJointValueNoUpdate(jointValues->getConfig(robotNode->getName())); } } @@ -744,9 +744,9 @@ namespace VirtualRobot { RobotNodePtr node; VR_ASSERT(robotNode); - for (size_t i = 0; i < robotNodes.size(); i++) + for (const auto & i : robotNodes) { - node = robotNodes.at(i); + node = i; if (node != robotNode && !robotNode->hasChild(node, true)) { @@ -772,9 +772,9 @@ namespace VirtualRobot ss << pre << "<RobotNodeSet name='" << name << "'>\n"; - for (size_t i = 0; i < robotNodes.size(); i++) + for (auto & robotNode : robotNodes) { - ss << pre << t << "<Node name='" << robotNodes[i]->getName() << "'/>\n"; + ss << pre << t << "<Node name='" << robotNode->getName() << "'/>\n"; } ss << pre << "</RobotNodeSet>\n"; diff --git a/VirtualRobot/RuntimeEnvironment.cpp b/VirtualRobot/RuntimeEnvironment.cpp index 09048cdd763274834f607ac06f42665a3b3751bf..7ffdb66916c9860ec543b62349234c652433faa1 100644 --- a/VirtualRobot/RuntimeEnvironment.cpp +++ b/VirtualRobot/RuntimeEnvironment.cpp @@ -125,9 +125,9 @@ namespace VirtualRobot // silently skip this error (e.g. device not ready, permission denied etc) } - for (size_t i = 0; i < dataPaths.size(); i++) + for (auto & dataPath : dataPaths) { - boost::filesystem::path p(dataPaths[i]); + boost::filesystem::path p(dataPath); boost::filesystem::path fnComplete = boost::filesystem::operator/(p, fn); @@ -168,9 +168,9 @@ namespace VirtualRobot ("data-path", boost::program_options::value< std::vector< std::string > >()->composing(), "Set data path. Multiple data paths are allowed.") ; - for (size_t i = 0; i < processKeys.size(); i++) + for (auto & processKey : processKeys) desc.add_options() - (processKeys[i].c_str(), boost::program_options::value< std::vector< std::string > >(), processKeys[i].c_str()) + (processKey.c_str(), boost::program_options::value< std::vector< std::string > >(), processKey.c_str()) ; boost::program_options::parsed_options parsed = @@ -187,28 +187,28 @@ namespace VirtualRobot //VR_INFO << "Data paths are: " << endl; std::vector< std::string > dp = vm["data-path"].as< std::vector< std::string > >(); - for (size_t i = 0; i < dp.size(); i++) + for (const auto & i : dp) { - addDataPath(dp[i]); + addDataPath(i); //VR_INFO << dp[i] << "\n"; } } // process generic keys - for (size_t i = 0; i < processKeys.size(); i++) + for (auto & processKey : processKeys) { - if (vm.count(processKeys[i].c_str())) + if (vm.count(processKey.c_str())) { - std::vector< std::string > dp = vm[processKeys[i].c_str()].as< std::vector< std::string > >(); + std::vector< std::string > dp = vm[processKey.c_str()].as< std::vector< std::string > >(); if (dp.size() > 1) { - VR_WARNING << "More than one parameter for key " << processKeys[i] << ". taking the first one..." << endl; + VR_WARNING << "More than one parameter for key " << processKey << ". taking the first one..." << endl; } if (dp.size() > 0) { - addKeyValuePair(processKeys[i], dp[0]); // take the first one... + addKeyValuePair(processKey, dp[0]); // take the first one... } } @@ -217,9 +217,9 @@ namespace VirtualRobot // collect unrecognized arguments std::vector<std::string> options = boost::program_options::collect_unrecognized(parsed.options, boost::program_options::include_positional); - for (size_t i = 0; i < options.size(); i++) + for (const auto & option : options) { - unrecognizedOptions.push_back(options[i]); + unrecognizedOptions.push_back(option); } @@ -295,18 +295,18 @@ namespace VirtualRobot cout << " *********** Simox RuntimeEnvironment ************* " << endl; cout << "Data paths:" << endl; - for (size_t i = 0; i < dataPaths.size(); i++) + for (const auto & dataPath : dataPaths) { - cout << " * " << dataPaths[i] << endl; + cout << " * " << dataPath << endl; } if (processKeys.size() > 0) { cout << "Known keys:" << endl; - for (size_t i = 0; i < processKeys.size(); i++) + for (const auto & processKey : processKeys) { - cout << " * " << processKeys[i] << endl; + cout << " * " << processKey << endl; } } @@ -326,9 +326,9 @@ namespace VirtualRobot { cout << "Unrecognized options:" << endl; - for (size_t i = 0; i < unrecognizedOptions.size(); i++) + for (const auto & unrecognizedOption : unrecognizedOptions) { - cout << " * <" << unrecognizedOptions[i] << ">" << endl; + cout << " * <" << unrecognizedOption << ">" << endl; } } diff --git a/VirtualRobot/Scene.cpp b/VirtualRobot/Scene.cpp index 526c13dfa8f0283ac37e46a1659bff12be503b8e..eaa2bb3989fcec274b316e81c8bc02ae4d500500 100644 --- a/VirtualRobot/Scene.cpp +++ b/VirtualRobot/Scene.cpp @@ -224,9 +224,9 @@ namespace VirtualRobot { THROW_VR_EXCEPTION_IF(!robot, "NULL data"); - for (std::vector< RobotPtr >::const_iterator i = robots.begin(); i != robots.end(); i++) + for (const auto & i : robots) { - if (*i == robot) + if (i == robot) { return true; } @@ -237,9 +237,9 @@ namespace VirtualRobot bool Scene::hasRobot(const std::string& name) const { - for (std::vector< RobotPtr >::const_iterator i = robots.begin(); i != robots.end(); i++) + for (const auto & robot : robots) { - if ((*i)->getName() == name) + if (robot->getName() == name) { return true; } @@ -252,9 +252,9 @@ namespace VirtualRobot { THROW_VR_EXCEPTION_IF(!obstacle, "NULL data"); - for (std::vector< ObstaclePtr >::const_iterator i = obstacles.begin(); i != obstacles.end(); i++) + for (const auto & i : obstacles) { - if (*i == obstacle) + if (i == obstacle) { return true; } @@ -265,9 +265,9 @@ namespace VirtualRobot bool Scene::hasObstacle(const std::string& name) const { - for (std::vector< ObstaclePtr >::const_iterator i = obstacles.begin(); i != obstacles.end(); i++) + for (const auto & obstacle : obstacles) { - if ((*i)->getName() == name) + if (obstacle->getName() == name) { return true; } @@ -282,9 +282,9 @@ namespace VirtualRobot { THROW_VR_EXCEPTION_IF(!t, "NULL data"); - for (std::vector< TrajectoryPtr >::const_iterator i = trajectories.begin(); i != trajectories.end(); i++) + for (const auto & trajectorie : trajectories) { - if (*i == t) + if (trajectorie == t) { return true; } @@ -295,9 +295,9 @@ namespace VirtualRobot bool Scene::hasTrajectory(const std::string& name) const { - for (std::vector< TrajectoryPtr >::const_iterator i = trajectories.begin(); i != trajectories.end(); i++) + for (const auto & trajectorie : trajectories) { - if ((*i)->getName() == name) + if (trajectorie->getName() == name) { return true; } @@ -311,9 +311,9 @@ namespace VirtualRobot { THROW_VR_EXCEPTION_IF(!manipulationObject, "NULL data"); - for (std::vector< ManipulationObjectPtr >::const_iterator i = manipulationObjects.begin(); i != manipulationObjects.end(); i++) + for (const auto & i : manipulationObjects) { - if (*i == manipulationObject) + if (i == manipulationObject) { return true; } @@ -324,9 +324,9 @@ namespace VirtualRobot bool Scene::hasManipulationObject(const std::string& name) const { - for (std::vector< ManipulationObjectPtr >::const_iterator i = manipulationObjects.begin(); i != manipulationObjects.end(); i++) + for (const auto & manipulationObject : manipulationObjects) { - if ((*i)->getName() == name) + if (manipulationObject->getName() == name) { return true; } @@ -406,9 +406,9 @@ namespace VirtualRobot void Scene::registerRobotConfig(RobotPtr robot, std::vector<RobotConfigPtr> configs) { - for (size_t i = 0; i < configs.size(); i++) + for (const auto & config : configs) { - registerRobotConfig(robot, configs[i]); + registerRobotConfig(robot, config); } } @@ -463,9 +463,9 @@ namespace VirtualRobot THROW_VR_EXCEPTION_IF(!config, "NULL data"); std::vector< RobotConfigPtr > configs = robotConfigs[robot]; - for (std::vector< RobotConfigPtr >::iterator i = configs.begin(); i != configs.end(); i++) + for (auto & i : configs) { - if (*i == config) + if (i == config) { return true; } @@ -479,9 +479,9 @@ namespace VirtualRobot THROW_VR_EXCEPTION_IF(!robot, "NULL data"); std::vector< RobotConfigPtr > configs = robotConfigs[robot]; - for (std::vector< RobotConfigPtr >::iterator i = configs.begin(); i != configs.end(); i++) + for (auto & config : configs) { - if ((*i)->getName() == name) + if (config->getName() == name) { return true; } @@ -493,11 +493,11 @@ namespace VirtualRobot VirtualRobot::RobotConfigPtr Scene::getRobotConfig(const std::string& robotName, const std::string& name) { - for (std::map< RobotPtr, std::vector< RobotConfigPtr > >::iterator i = robotConfigs.begin(); i != robotConfigs.end(); i++) + for (auto & robotConfig : robotConfigs) { - if (i->first->getName() == robotName) + if (robotConfig.first->getName() == robotName) { - return getRobotConfig(i->first, name); + return getRobotConfig(robotConfig.first, name); } } @@ -510,11 +510,11 @@ namespace VirtualRobot THROW_VR_EXCEPTION_IF(!robot, "NULL data"); std::vector< RobotConfigPtr > configs = robotConfigs[robot]; - for (std::vector< RobotConfigPtr >::iterator i = configs.begin(); i != configs.end(); i++) + for (auto & config : configs) { - if ((*i)->getName() == name) + if (config->getName() == name) { - return *i; + return config; } } @@ -546,11 +546,11 @@ namespace VirtualRobot { std::vector< TrajectoryPtr > res; - for (size_t i = 0; i < trajectories.size(); i++) + for (auto & trajectorie : trajectories) { - if (trajectories[i]->getRobotName() == robotName) + if (trajectorie->getRobotName() == robotName) { - res.push_back(trajectories[i]); + res.push_back(trajectorie); } } @@ -642,9 +642,9 @@ namespace VirtualRobot { THROW_VR_EXCEPTION_IF(!sos, "NULL data"); - for (std::vector< SceneObjectSetPtr >::const_iterator i = sceneObjectSets.begin(); i != sceneObjectSets.end(); i++) + for (const auto & sceneObjectSet : sceneObjectSets) { - if (*i == sos) + if (sceneObjectSet == sos) { return true; } @@ -655,9 +655,9 @@ namespace VirtualRobot bool Scene::hasSceneObjectSet(const std::string& name) const { - for (std::vector< SceneObjectSetPtr >::const_iterator i = sceneObjectSets.begin(); i != sceneObjectSets.end(); i++) + for (const auto & sceneObjectSet : sceneObjectSets) { - if ((*i)->getName() == name) + if (sceneObjectSet->getName() == name) { return true; } @@ -698,12 +698,12 @@ namespace VirtualRobot ss << "\n"; // process robots - for (size_t i = 0; i < robots.size(); i++) + for (auto & robot : robots) { - std::string rob = robots[i]->getName(); - RobotConfigPtr currentConfig = robots[i]->getConfig(); + std::string rob = robot->getName(); + RobotConfigPtr currentConfig = robot->getConfig(); ss << "\t<Robot name='" << rob << "' initConfig='" << currentConfig->getName() << "'>\n"; - std::string robFile = robots[i]->getFilename(); + std::string robFile = robot->getFilename(); if (!basePath.empty()) { @@ -713,7 +713,7 @@ namespace VirtualRobot ss << "\t\t<File>" << robFile << "</File>\n"; // store global pose (if not identity) - Eigen::Matrix4f gp = robots[i]->getGlobalPose(); + Eigen::Matrix4f gp = robot->getGlobalPose(); if (!gp.isIdentity()) { @@ -728,11 +728,11 @@ namespace VirtualRobot ss << currentConfig->toXML(2); // store all other configs for robot - std::vector<RobotConfigPtr> rc = getRobotConfigs(robots[i]); + std::vector<RobotConfigPtr> rc = getRobotConfigs(robot); - for (size_t j = 0; j < rc.size(); j++) + for (auto & j : rc) { - ss << rc[j]->toXML(2); + ss << j->toXML(2); } ss << "\t</Robot>\n"; @@ -740,30 +740,30 @@ namespace VirtualRobot } // process manipulation objects - for (size_t i = 0; i < manipulationObjects.size(); i++) + for (auto & manipulationObject : manipulationObjects) { - ss << manipulationObjects[i]->toXML(basePath, 1, true); + ss << manipulationObject->toXML(basePath, 1, true); ss << "\n"; } // process obstacles - for (size_t i = 0; i < obstacles.size(); i++) + for (auto & obstacle : obstacles) { - ss << obstacles[i]->toXML(basePath, 1); + ss << obstacle->toXML(basePath, 1); ss << "\n"; } // process sceneObjectSets - for (size_t i = 0; i < sceneObjectSets.size(); i++) + for (auto & sceneObjectSet : sceneObjectSets) { - ss << sceneObjectSets[i]->toXML(1); + ss << sceneObjectSet->toXML(1); ss << "\n"; } // process trajectories - for (size_t i = 0; i < trajectories.size(); i++) + for (auto & trajectorie : trajectories) { - ss << trajectories[i]->toXML(1); + ss << trajectorie->toXML(1); ss << "\n"; } diff --git a/VirtualRobot/SceneObjectSet.cpp b/VirtualRobot/SceneObjectSet.cpp index 1b5dae76fc726989e1468d1f76133ad7947d0227..1ebbc663bf86db359f3bebdfe7e8e49e5ea17b7f 100644 --- a/VirtualRobot/SceneObjectSet.cpp +++ b/VirtualRobot/SceneObjectSet.cpp @@ -62,8 +62,8 @@ namespace VirtualRobot return false; } - for (unsigned i = 0; i < sceneObjects.size(); i++) - if (sceneObjects[i] == sceneObject) + for (const auto & i : sceneObjects) + if (i == sceneObject) { VR_WARNING << "col model already added, in: " << name << endl; return false; @@ -91,9 +91,9 @@ namespace VirtualRobot std::vector< SceneObjectPtr > so = sceneObjectSet->getSceneObjects(); - for (size_t i = 0; i < so.size(); i++) + for (const auto & i : so) { - if (!addSceneObject(so[i])) + if (!addSceneObject(i)) { return false; } @@ -116,15 +116,15 @@ namespace VirtualRobot bool SceneObjectSet::addSceneObjects(std::vector<RobotNodePtr> robotNodes) { - for (size_t i = 0; i < robotNodes.size(); i++) + for (auto & robotNode : robotNodes) { - SceneObjectPtr cm = boost::dynamic_pointer_cast<SceneObject>(robotNodes[i]); + SceneObjectPtr cm = boost::dynamic_pointer_cast<SceneObject>(robotNode); if (cm) { if (colChecker != cm->getCollisionChecker()) { - VR_WARNING << "col model of " << robotNodes[i]->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() << endl; } else { @@ -221,9 +221,9 @@ namespace VirtualRobot bool SceneObjectSet::getCurrentSceneObjectConfig(std::map< SceneObjectPtr, Eigen::Matrix4f >& storeConfig) { - for (std::vector< SceneObjectPtr >::iterator iter = sceneObjects.begin(); iter != sceneObjects.end(); iter++) + for (auto & sceneObject : sceneObjects) { - storeConfig[(*iter)] = (*iter)->getGlobalPose(); + storeConfig[sceneObject] = sceneObject->getGlobalPose(); } return true; @@ -231,9 +231,9 @@ namespace VirtualRobot bool SceneObjectSet::hasSceneObject(SceneObjectPtr sceneObject) { - for (std::vector< SceneObjectPtr >::iterator iter = sceneObjects.begin(); iter != sceneObjects.end(); iter++) + for (auto & iter : sceneObjects) { - if ((*iter) == sceneObject) + if (iter == sceneObject) { return true; } @@ -246,11 +246,11 @@ namespace VirtualRobot { std::vector< CollisionModelPtr > result; - for (size_t i = 0; i < sceneObjects.size(); i++) + for (auto & sceneObject : sceneObjects) { - if (sceneObjects[i]->getCollisionModel()) + if (sceneObject->getCollisionModel()) { - result.push_back(sceneObjects[i]->getCollisionModel()); + result.push_back(sceneObject->getCollisionModel()); } } @@ -286,9 +286,9 @@ namespace VirtualRobot ss << pre << "<SceneObjectSet name='" << name << "'>\n"; - for (size_t i = 0; i < sceneObjects.size(); i++) + for (auto & sceneObject : sceneObjects) { - ss << pre << t << "<SceneObject name='" << sceneObjects[i]->getName() << "'/>\n"; + ss << pre << t << "<SceneObject name='" << sceneObject->getName() << "'/>\n"; } ss << pre << "</SceneObjectSet>\n"; @@ -299,9 +299,9 @@ namespace VirtualRobot { SceneObjectSetPtr result(new SceneObjectSet(newName, colChecker)); - for (size_t i = 0; i < sceneObjects.size(); i++) + for (const auto & sceneObject : sceneObjects) { - result->addSceneObject(sceneObjects[i]); + result->addSceneObject(sceneObject); } return result; @@ -312,9 +312,9 @@ namespace VirtualRobot { SceneObjectSetPtr result(new SceneObjectSet(newName, newColChecker)); - for (size_t i = 0; i < sceneObjects.size(); i++) + for (auto & sceneObject : sceneObjects) { - SceneObjectPtr o = sceneObjects[i]->clone(sceneObjects[i]->getName(), newColChecker); + SceneObjectPtr o = sceneObject->clone(sceneObject->getName(), newColChecker); result->addSceneObject(o); } @@ -327,16 +327,16 @@ namespace VirtualRobot std::vector<VisualizationNodePtr> visus; std::vector<CollisionModelPtr> cols; - for (size_t i = 0; i < sceneObjects.size(); i++) + for (auto & sceneObject : sceneObjects) { - if (sceneObjects[i]->getVisualization()) + if (sceneObject->getVisualization()) { - visus.push_back(sceneObjects[i]->getVisualization()); + visus.push_back(sceneObject->getVisualization()); } - if (sceneObjects[i]->getCollisionModel()) + if (sceneObject->getCollisionModel()) { - cols.push_back(sceneObjects[i]->getCollisionModel()); + cols.push_back(sceneObject->getCollisionModel()); } } diff --git a/VirtualRobot/SphereApproximator.cpp b/VirtualRobot/SphereApproximator.cpp index 1a4a7c1b314a547d11ac2c03a437be4715292b17..c3b9af9f6cb47e4e5d27a9b37b7e85fff4724ebc 100644 --- a/VirtualRobot/SphereApproximator.cpp +++ b/VirtualRobot/SphereApproximator.cpp @@ -122,9 +122,9 @@ namespace VirtualRobot setVec(v[2], -fSqrt3, fSqrt3, -fSqrt3); setVec(v[3], fSqrt3, -fSqrt3, -fSqrt3); - for (int i = 0 ; i < 4 ; i++) + for (const auto & i : v) { - gd.vertices.push_back(v[i]); + gd.vertices.push_back(i); } // structure describing a tetrahedron @@ -134,12 +134,12 @@ namespace VirtualRobot f[2].set(3, 2, 4); f[3].set(4, 1, 3); - for (int i = 0 ; i < 4 ; i++) + for (auto & i : f) { - f[i].id1--; - f[i].id2--; - f[i].id3--; - gd.faces.push_back(f[i]); + i.id1--; + i.id2--; + i.id3--; + gd.faces.push_back(i); } } @@ -154,9 +154,9 @@ namespace VirtualRobot setVec(v[4], 0, 0, 1); setVec(v[5], 0, 0, -1); - for (int i = 0 ; i < 6 ; i++) + for (const auto & i : v) { - gd.vertices.push_back(v[i]); + gd.vertices.push_back(i); } // Join vertices to create a unit octahedron @@ -170,12 +170,12 @@ namespace VirtualRobot f[6].set(2, 4, 6); f[7].set(4, 1, 6); - for (int i = 0 ; i < 8 ; i++) + for (auto & i : f) { - f[i].id1--; - f[i].id2--; - f[i].id3--; - gd.faces.push_back(f[i]); + i.id1--; + i.id2--; + i.id3--; + gd.faces.push_back(i); } } @@ -200,9 +200,9 @@ namespace VirtualRobot setVec(v[10], 0, -tau, -one); setVec(v[11], 0, tau, -one); - for (int i = 0 ; i < 12 ; i++) + for (const auto & i : v) { - gd.vertices.push_back(v[i]); + gd.vertices.push_back(i); } @@ -229,12 +229,12 @@ namespace VirtualRobot f[18].set(8, 10, 3); f[19].set(7, 3, 11); - for (int i = 0 ; i < 20 ; i++) + for (auto & i : f) { - f[i].id1--; - f[i].id2--; - f[i].id3--; - gd.faces.push_back(f[i]); + i.id1--; + i.id2--; + i.id3--; + gd.faces.push_back(i); } } @@ -319,9 +319,9 @@ namespace VirtualRobot fa[2].set(nC_m, nB_m, nC); fa[3].set(nA_m, nB_m, nC_m); - for (int i = 0 ; i < 4 ; i++) + for (const auto & i : fa) { - newFaces.push_back(fa[i]); + newFaces.push_back(i); } } diff --git a/VirtualRobot/TimeOptimalTrajectory/Path.cpp b/VirtualRobot/TimeOptimalTrajectory/Path.cpp index d6398d49630e176d239dd6f13c0a915b3483301b..fe51f30425a256a40943b5cca2baa67f646b50f6 100644 --- a/VirtualRobot/TimeOptimalTrajectory/Path.cpp +++ b/VirtualRobot/TimeOptimalTrajectory/Path.cpp @@ -205,13 +205,13 @@ namespace VirtualRobot } // create list of switching point candidates, calculate total path length and absolute positions of path segments - for(list<PathSegment*>::iterator segment = pathSegments.begin(); segment != pathSegments.end(); segment++) { - (*segment)->position = length; - list<double> localSwitchingPoints = (*segment)->getSwitchingPoints(); + for(auto & pathSegment : pathSegments) { + pathSegment->position = length; + list<double> localSwitchingPoints = pathSegment->getSwitchingPoints(); for(list<double>::const_iterator point = localSwitchingPoints.begin(); point != localSwitchingPoints.end(); point++) { switchingPoints.push_back(make_pair(length + *point, false)); } - length += (*segment)->getLength(); + length += pathSegment->getLength(); while(!switchingPoints.empty() && switchingPoints.back().first >= length) switchingPoints.pop_back(); switchingPoints.push_back(make_pair(length, true)); @@ -223,14 +223,14 @@ namespace VirtualRobot length(path.length), switchingPoints(path.switchingPoints) { - for(list<PathSegment*>::const_iterator it = path.pathSegments.begin(); it != path.pathSegments.end(); it++) { - pathSegments.push_back((*it)->clone()); + for(auto pathSegment : path.pathSegments) { + pathSegments.push_back(pathSegment->clone()); } } Path::~Path() { - for(list<PathSegment*>::iterator it = pathSegments.begin(); it != pathSegments.end(); it++) { - delete *it; + for(auto & pathSegment : pathSegments) { + delete pathSegment; } } diff --git a/VirtualRobot/TimeOptimalTrajectory/TimeOptimalTrajectory.cpp b/VirtualRobot/TimeOptimalTrajectory/TimeOptimalTrajectory.cpp index 9ed6c1ae841690d883d25e33147bfd7b81e64fe3..1498d88f7a8fc18220b6a7234b77861fca282b2e 100644 --- a/VirtualRobot/TimeOptimalTrajectory/TimeOptimalTrajectory.cpp +++ b/VirtualRobot/TimeOptimalTrajectory/TimeOptimalTrajectory.cpp @@ -106,11 +106,11 @@ namespace VirtualRobot file1.close(); ofstream file2("trajectory.txt"); - for(list<TimeOptimalTrajectoryStep>::const_iterator it = trajectory.begin(); it != trajectory.end(); it++) { - file2 << it->pathPos << " " << it->pathVel << endl; + for(const auto & it : trajectory) { + file2 << it.pathPos << " " << it.pathVel << endl; } - for(list<TimeOptimalTrajectoryStep>::const_iterator it = endTrajectory.begin(); it != endTrajectory.end(); it++) { - file2 << it->pathPos << " " << it->pathVel << endl; + for(const auto & it : endTrajectory) { + file2 << it.pathPos << " " << it.pathVel << endl; } file2.close(); } diff --git a/VirtualRobot/Tools/Gravity.cpp b/VirtualRobot/Tools/Gravity.cpp index 28e83045d3f8f0c8cb236bfb8bbf56e54ec3cd4d..b6c8d44fface6ffee21eb5500d4ab9beac4356c4 100644 --- a/VirtualRobot/Tools/Gravity.cpp +++ b/VirtualRobot/Tools/Gravity.cpp @@ -134,8 +134,8 @@ void Gravity::GravityData::init(SceneObjectPtr node, const std::vector<RobotNode } } - for (size_t i = 0; i < bodies.size(); ++i) { - if(thisNode == bodies.at(i)){ + for (const auto & bodie : bodies) { + if(thisNode == bodie){ computeCoM = true; // VR_INFO << "Computing com for " << thisNode->getName() << std::endl; } diff --git a/VirtualRobot/Util/xml/tinyxml2.cpp b/VirtualRobot/Util/xml/tinyxml2.cpp old mode 100755 new mode 100644 index fd27f7888d279e8f66d4fda506945f38a909bad8..8fff487289802cddc4924c9f6973cdb72c0924bb --- a/VirtualRobot/Util/xml/tinyxml2.cpp +++ b/VirtualRobot/Util/xml/tinyxml2.cpp @@ -326,8 +326,7 @@ const char* StrPair::GetStr() } else { bool entityFound = false; - for( int i = 0; i < NUM_ENTITIES; ++i ) { - const Entity& entity = entities[i]; + for(auto entity : entities) { if ( strncmp( p + 1, entity.pattern, entity.length ) == 0 && *( p + entity.length + 1 ) == ';' ) { // Found an entity - convert. @@ -2422,8 +2421,8 @@ XMLPrinter::XMLPrinter( FILE* file, bool compact, int depth ) : _entityFlag[i] = false; _restrictedEntityFlag[i] = false; } - for( int i=0; i<NUM_ENTITIES; ++i ) { - const char entityValue = entities[i].value; + for(auto entitie : entities) { + const char entityValue = entitie.value; const unsigned char flagIndex = (unsigned char)entityValue; TIXMLASSERT( flagIndex < ENTITY_RANGE ); _entityFlag[flagIndex] = true; @@ -2513,10 +2512,10 @@ void XMLPrinter::PrintString( const char* p, bool restricted ) p += toPrint; } bool entityPatternPrinted = false; - for( int i=0; i<NUM_ENTITIES; ++i ) { - if ( entities[i].value == *q ) { + for(auto entitie : entities) { + if ( entitie.value == *q ) { Putc( '&' ); - Write( entities[i].pattern, entities[i].length ); + Write( entitie.pattern, entitie.length ); Putc( ';' ); entityPatternPrinted = true; break; diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp index 72c1a89cbb3edaee8708e63563ffc2717be9c5e0..70bb6911a0f4fb34cf3d98fd9c3b3afa100fae8f 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp @@ -141,9 +141,8 @@ namespace VirtualRobot Eigen::Matrix4f currentTransform = Eigen::Matrix4f::Identity(); - for (std::vector<Primitive::PrimitivePtr>::const_iterator it = primitives.begin(); it != primitives.end(); it++) + for (auto p : primitives) { - Primitive::PrimitivePtr p = *it; currentTransform *= p->transform; SoSeparator* soSep = new SoSeparator(); SoNode* pNode = GetNodeFromPrimitive(p, boundingBox, color); @@ -1535,9 +1534,9 @@ namespace VirtualRobot SoSeparator* res = new SoSeparator; res->ref(); - for (size_t i = 0; i < contacts.size(); i++) + for (auto & contact : contacts) { - res->addChild(getCoinVisualization(contacts[i], frictionConeHeight, frictionConeRadius, scaleAccordingToApproachDir)); + res->addChild(getCoinVisualization(contact, frictionConeHeight, frictionConeRadius, scaleAccordingToApproachDir)); } res->unrefNoDelete(); @@ -4028,9 +4027,9 @@ namespace VirtualRobot std::vector<MathTools::Segment> s = oobb.getSegments(); - for (size_t i = 0; i < s.size(); i++) + for (const auto & i : s) { - sep->addChild(CreateSegmentVisualization(s[i], colorLine, lineSize)); + sep->addChild(CreateSegmentVisualization(i, colorLine, lineSize)); } res->addChild(sep); @@ -4339,10 +4338,9 @@ namespace VirtualRobot SoNode* result = n->copy(TRUE); // reset the changed ones back - for (std::vector<SoSFImage*>::iterator it = changedImages.begin(); - it != changedImages.end(); it++) + for (auto & changedImage : changedImages) { - (*it)->setDefault(TRUE); + changedImage->setDefault(TRUE); } return result; diff --git a/VirtualRobot/Visualization/TriMeshModel.cpp b/VirtualRobot/Visualization/TriMeshModel.cpp index 941ab1a65ff4eec805c015e08de23ec6fa91c085..a7d5aaaf9f2b4581847cf287cf4e1c1746d06f79 100644 --- a/VirtualRobot/Visualization/TriMeshModel.cpp +++ b/VirtualRobot/Visualization/TriMeshModel.cpp @@ -25,9 +25,9 @@ namespace VirtualRobot TriMeshModel::TriMeshModel(std::vector <triangle>& triangles) { - for (size_t i = 0; i < triangles.size(); i++) + for (auto & triangle : triangles) { - addTriangleWithFace(triangles[i].vertex1, triangles[i].vertex2, triangles[i].vertex3); + addTriangleWithFace(triangle.vertex1, triangle.vertex2, triangle.vertex3); } } @@ -794,9 +794,9 @@ namespace VirtualRobot { cout << "TriMeshModel Normals:" << endl; std::streamsize pr = cout.precision(2); - for (size_t i = 0; i < faces.size(); i++) + for (auto & face : faces) { - cout << "<" << faces[i].normal(0) << "," << faces[i].normal(1) << "," << faces[i].normal(2) << ">,"; + cout << "<" << face.normal(0) << "," << face.normal(1) << "," << face.normal(2) << ">,"; } cout.precision(pr); } @@ -816,9 +816,9 @@ namespace VirtualRobot { cout << "TriMeshModel Faces (vertex indices):" << endl; std::streamsize pr = cout.precision(2); - for (size_t i = 0; i < faces.size(); i++) + for (auto & face : faces) { - cout << faces[i].id1 << "," << faces[i].id2 << "," << faces[i].id3 << endl; + cout << face.id1 << "," << face.id2 << "," << face.id3 << endl; } cout.precision(pr); } diff --git a/VirtualRobot/Workspace/WorkspaceGrid.cpp b/VirtualRobot/Workspace/WorkspaceGrid.cpp index 2b9c67d8ff90d2ee1a3ec670862c16b4165139ab..932987cc5f82eda43cb7eefeff77f58d60dcf832 100644 --- a/VirtualRobot/Workspace/WorkspaceGrid.cpp +++ b/VirtualRobot/Workspace/WorkspaceGrid.cpp @@ -275,13 +275,13 @@ namespace VirtualRobot float x, y; - for (int i = 0; i < (int)wsData.size(); i++) + for (auto & i : wsData) { - Eigen::Matrix4f tmpPos2 = graspGlobal * wsData[i]->transformation.inverse(); + Eigen::Matrix4f tmpPos2 = graspGlobal * i->transformation.inverse(); x = tmpPos2(0, 3); y = tmpPos2(1, 3); - setEntryCheckNeighbors(x, y, wsData[i]->value, grasp); + setEntryCheckNeighbors(x, y, i->value, grasp); //setEntry(x,y,vData[i].value); } } diff --git a/VirtualRobot/Workspace/WorkspaceRepresentation.cpp b/VirtualRobot/Workspace/WorkspaceRepresentation.cpp index cfb3b81b2f466cc430bf16448bc4b2a475175bf3..4de5f5329d23cdf3de71a536b356e0a34f2b1162 100644 --- a/VirtualRobot/Workspace/WorkspaceRepresentation.cpp +++ b/VirtualRobot/Workspace/WorkspaceRepresentation.cpp @@ -251,16 +251,16 @@ namespace VirtualRobot // Check joint limits std::vector<RobotNodePtr> nodes = nodeSet->getAllRobotNodes(); - for (std::vector<RobotNodePtr>::iterator n = nodes.begin(); n != nodes.end(); n++) + for (auto & node : nodes) { float limits[2]; FileIO::readArray<float>(limits, 2, file); //limits[0] = (int)(FileIO::read<ioIntTypeRead>(file)); //limits[1] = (int)(FileIO::read<ioIntTypeRead>(file)); - if (fabs((*n)->getJointLimitLo() - limits[0]) > 0.01 || fabs((*n)->getJointLimitHi() - limits[1]) > 0.01) + if (fabs(node->getJointLimitLo() - limits[0]) > 0.01 || fabs(node->getJointLimitHi() - limits[1]) > 0.01) { - VR_WARNING << "Joint limit mismatch for " << (*n)->getName() << ", min: " << (*n)->getJointLimitLo() << " / " << limits[0] << ", max: " << (*n)->getJointLimitHi() << " / " << limits[1] << std::endl; + VR_WARNING << "Joint limit mismatch for " << node->getName() << ", min: " << node->getJointLimitLo() << " / " << limits[0] << ", max: " << node->getJointLimitHi() << " / " << limits[1] << std::endl; } } } @@ -308,9 +308,9 @@ namespace VirtualRobot discretizeStepTranslation = FileIO::read<float>(file); discretizeStepRotation = FileIO::read<float>(file); - for (int i = 0; i < 6; i++) + for (int & numVoxel : numVoxels) { - numVoxels[i] = (int)(FileIO::read<ioIntTypeRead>(file)); + numVoxel = (int)(FileIO::read<ioIntTypeRead>(file)); } //FileIO::readArray<int>(numVoxels, 6, file); @@ -529,10 +529,10 @@ namespace VirtualRobot const std::vector<RobotNodePtr> nodes = nodeSet->getAllRobotNodes(); FileIO::write<ioIntTypeWrite>(file, (ioIntTypeWrite)(nodes.size())); - for (std::vector<RobotNodePtr>::const_iterator n = nodes.begin(); n != nodes.end(); n++) + for (const auto & node : nodes) { - FileIO::write<float>(file, (*n)->getJointLimitLo()); - FileIO::write<float>(file, (*n)->getJointLimitHi()); + FileIO::write<float>(file, node->getJointLimitLo()); + FileIO::write<float>(file, node->getJointLimitHi()); } // TCP name @@ -576,9 +576,9 @@ namespace VirtualRobot // Number of voxels //FileIO::writeArray<ioIntTypeWrite>(file, numVoxels, 6); - for (int i = 0; i < 6; i++) + for (int & numVoxel : numVoxels) { - FileIO::write<ioIntTypeWrite>(file, (ioIntTypeWrite)(numVoxels[i])); + FileIO::write<ioIntTypeWrite>(file, (ioIntTypeWrite)numVoxel); } FileIO::write<ioIntTypeWrite>(file, (ioIntTypeWrite)(data->getVoxelFilledCount())); @@ -1056,34 +1056,34 @@ namespace VirtualRobot cout << type << " workspace extend (as defined on construction):" << endl; cout << "Min boundary (local): "; - for (int i = 0; i < 6; i++) + for (float minBound : minBounds) { - cout << minBounds[i] << ","; + cout << minBound << ","; } cout << endl; cout << "Max boundary (local): "; - for (int i = 0; i < 6; i++) + for (float maxBound : maxBounds) { - cout << maxBounds[i] << ","; + cout << maxBound << ","; } cout << endl; cout << "6D values achieved during buildup:" << endl; cout << "Minimum 6D values: "; - for (int i = 0; i < 6; i++) + for (float achievedMinValue : achievedMinValues) { - cout << achievedMinValues[i] << ","; + cout << achievedMinValue << ","; } cout << endl; cout << "Maximum 6D values: "; - for (int i = 0; i < 6; i++) + for (float achievedMaxValue : achievedMaxValues) { - cout << achievedMaxValues[i] << ","; + cout << achievedMaxValue << ","; } cout << endl; @@ -1397,9 +1397,9 @@ namespace VirtualRobot int sum = 0; int count = 0; - for (int i = 0; i < 6; i++) + for (unsigned int & i : x) { - x[i]--; + i--; if (isCovered(x)) { @@ -1407,8 +1407,8 @@ namespace VirtualRobot count++; } - x[i]++; - x[i]++; + i++; + i++; if (isCovered(x)) { @@ -1416,7 +1416,7 @@ namespace VirtualRobot count++; } - x[i]--; + i--; } if (count >= (int)minNeighbors) @@ -1768,18 +1768,18 @@ namespace VirtualRobot storeMinBBox = quadPos[0]; storeMaxBBox = quadPos[0]; - for (int k = 0; k < 8; k++) + for (auto & quadPo : quadPos) { for (int i = 0; i < 3; i++) { - if (quadPos[k](i) < storeMinBBox(i)) + if (quadPo(i) < storeMinBBox(i)) { - storeMinBBox(i) = quadPos[k](i); + storeMinBBox(i) = quadPo(i); } - if (quadPos[k](i) > storeMaxBBox(i)) + if (quadPo(i) > storeMaxBBox(i)) { - storeMaxBBox(i) = quadPos[k](i); + storeMaxBBox(i) = quadPo(i); } } } diff --git a/VirtualRobot/Workspace/tests/VoxelTreeTest.cpp b/VirtualRobot/Workspace/tests/VoxelTreeTest.cpp index dd9ca457ebfbba9104f51b50bedd85bd2680aaa0..e337daf8ad827f8bc7fe2210b5c49c2fd5012038 100644 --- a/VirtualRobot/Workspace/tests/VoxelTreeTest.cpp +++ b/VirtualRobot/Workspace/tests/VoxelTreeTest.cpp @@ -66,9 +66,9 @@ BOOST_AUTO_TEST_CASE(VoxelTreeEntriesTest) VirtualRobot::VoxelTree6D<unsigned char> v(minB, maxB, 20.0f, 1.0f); float pos[6]; - for (int i = 0; i < 6; i++) + for (float & po : pos) { - pos[i] = 0; + po = 0; } unsigned char* c = v.getEntry(pos); @@ -101,9 +101,9 @@ BOOST_AUTO_TEST_CASE(VoxelTreeNDEntriesTest) VirtualRobot::VoxelTreeND<unsigned char, N> v(minB, maxB, discr, true); float pos[N]; - for (unsigned int i = 0; i < N; i++) + for (float & po : pos) { - pos[i] = 0; + po = 0; } unsigned char* c = v.getEntry(pos); @@ -149,17 +149,17 @@ BOOST_AUTO_TEST_CASE(VoxelTreeNDSaveLoad) for (unsigned int i = 0; i < TEST_LOOPS; i++) { - for (unsigned int j = 0; j < N; j++) + for (float & po : pos) { - pos[j] = float(rand() % 10000) / 10000.0f * 200.0f - 100.0f; + po = float(rand() % 10000) / 10000.0f * 200.0f - 100.0f; } v.setEntry(pos, rand() % 255); } - for (unsigned int i = 0; i < N; i++) + for (float & po : pos) { - pos[i] = 17.0f; + po = 17.0f; } v.setEntry(pos, 10); @@ -194,14 +194,14 @@ BOOST_AUTO_TEST_CASE(VoxelTreeNDIterator) const int TEST_LOOPS = 10000; float pos[TEST_LOOPS][N]; - for (int i = 0; i < TEST_LOOPS; i++) + for (auto & po : pos) { - for (unsigned int j = 0; j < N; j++) + for (float & j : po) { - pos[i][j] = float(rand() % 10000) / 10000.0f * 200.0f - 100.0f; + j = float(rand() % 10000) / 10000.0f * 200.0f - 100.0f; } - v.setEntry(pos[i], rand() % 255); + v.setEntry(po, rand() % 255); } VirtualRobot::VoxelTreeND<unsigned char, N>::ElementIterator it; @@ -237,9 +237,9 @@ BOOST_AUTO_TEST_CASE(VoxelTreeNDMem) float pos[N]; - for (unsigned int j = 0; j < N; j++) + for (float & po : pos) { - pos[j] = float(rand() % 10000) / 10000.0f * 200.0f - 100.0f; + po = float(rand() % 10000) / 10000.0f * 200.0f - 100.0f; } v.setEntry(pos, rand() % 255); diff --git a/VirtualRobot/XML/BaseIO.cpp b/VirtualRobot/XML/BaseIO.cpp index b6b389f622e0e2c8c6dcf639f89136571de62a85..84ff2937bccbea709663e40ac8b303e8fa655f1c 100644 --- a/VirtualRobot/XML/BaseIO.cpp +++ b/VirtualRobot/XML/BaseIO.cpp @@ -356,16 +356,16 @@ namespace VirtualRobot Units uAngle("rad"); Units uLength("mm"); - for (size_t i = 0; i < unitsAttr.size(); i++) + for (auto & i : unitsAttr) { - if (unitsAttr[i].isAngle()) + if (i.isAngle()) { - uAngle = unitsAttr[i]; + uAngle = i; } - if (unitsAttr[i].isLength()) + if (i.isLength()) { - uLength = unitsAttr[i]; + uLength = i; } } @@ -457,9 +457,9 @@ namespace VirtualRobot getAllAttributes(node, "unitsAngle", attrStr); getAllAttributes(node, "unitsTime", attrStr); - for (size_t i = 0; i < attrStr.size(); i++) + for (auto & i : attrStr) { - Units unitsAttribute(getLowerCase(attrStr[i].c_str())); + Units unitsAttribute(getLowerCase(i.c_str())); result.push_back(unitsAttribute); } @@ -1343,16 +1343,16 @@ namespace VirtualRobot Units uWeight("kg"); Units uLength("m"); - for (size_t i = 0; i < unitsAttr.size(); i++) + for (auto & i : unitsAttr) { - if (unitsAttr[i].isWeight()) + if (i.isWeight()) { - uWeight = unitsAttr[i]; + uWeight = i; } - if (unitsAttr[i].isLength()) + if (i.isLength()) { - uLength = unitsAttr[i]; + uLength = i; } } @@ -1737,11 +1737,11 @@ namespace VirtualRobot RobotPtr r; - for (size_t i = 0; i < robots.size(); i++) + for (auto & robot : robots) { - if (robots[i]->getType() == robotName) + if (robot->getType() == robotName) { - r = robots[i]; + r = robot; break; } } diff --git a/VirtualRobot/XML/ObjectIO.cpp b/VirtualRobot/XML/ObjectIO.cpp index 058b311e2e40bc1329d638e09e6a1cb77c06b6d8..34c3138b61da7cf5c5443107b33dae0f279b0bc2 100644 --- a/VirtualRobot/XML/ObjectIO.cpp +++ b/VirtualRobot/XML/ObjectIO.cpp @@ -135,9 +135,9 @@ namespace VirtualRobot // create & register configs std::map< std::string, float > rc; - for (size_t i = 0; i < configDefinitions.size(); i++) + for (auto & configDefinition : configDefinitions) { - rc[ configDefinitions[i].name ] = configDefinitions[i].value; + rc[ configDefinition.name ] = configDefinition.value; } grasp->setConfiguration(rc); @@ -344,9 +344,9 @@ namespace VirtualRobot // build object ManipulationObjectPtr object(new ManipulationObject(objName, visualizationNode, collisionModel, physics)); - for (size_t i = 0; i < graspSets.size(); i++) + for (const auto & graspSet : graspSets) { - object->addGraspSet(graspSets[i]); + object->addGraspSet(graspSet); } object->setGlobalPose(globalPose); diff --git a/VirtualRobot/XML/RobotIO.cpp b/VirtualRobot/XML/RobotIO.cpp index c35b7c364a1b99f733a73eb6ff921157834f9285..812f1209cc9e82870dbe056ec9582c8753c27175 100644 --- a/VirtualRobot/XML/RobotIO.cpp +++ b/VirtualRobot/XML/RobotIO.cpp @@ -335,21 +335,21 @@ namespace VirtualRobot Units uLength("m"); Units uAngle("rad"); - for (size_t i = 0; i < unitsAttr.size(); i++) + for (auto & i : unitsAttr) { - if (unitsAttr[i].isTime()) + if (i.isTime()) { - uTime = unitsAttr[i]; + uTime = i; } - if (unitsAttr[i].isLength()) + if (i.isLength()) { - uLength = unitsAttr[i]; + uLength = i; } - if (unitsAttr[i].isAngle()) + if (i.isAngle()) { - uAngle = unitsAttr[i]; + uAngle = i; } } @@ -388,21 +388,21 @@ namespace VirtualRobot Units uLength("m"); Units uAngle("rad"); - for (size_t i = 0; i < unitsAttr.size(); i++) + for (auto & i : unitsAttr) { - if (unitsAttr[i].isTime()) + if (i.isTime()) { - uTime = unitsAttr[i]; + uTime = i; } - if (unitsAttr[i].isLength()) + if (i.isLength()) { - uLength = unitsAttr[i]; + uLength = i; } - if (unitsAttr[i].isAngle()) + if (i.isAngle()) { - uAngle = unitsAttr[i]; + uAngle = i; } } @@ -438,11 +438,11 @@ namespace VirtualRobot std::vector< Units > unitsAttr = getUnitsAttributes(node); Units uLength("m"); - for (size_t i = 0; i < unitsAttr.size(); i++) + for (auto & i : unitsAttr) { - if (unitsAttr[i].isLength()) + if (i.isLength()) { - uLength = unitsAttr[i]; + uLength = i; } } @@ -738,9 +738,9 @@ namespace VirtualRobot robotNode = processJointNode(jointNodeXML, robotNodeName, robo, visualizationNode, collisionModel, physics, rntype, transformMatrix); // process sensors - for (size_t i = 0; i < sensorTags.size(); i++) + for (auto & sensorTag : sensorTags) { - processSensor(robotNode, sensorTags[i], loadMode, basePath); + processSensor(robotNode, sensorTag, loadMode, basePath); } return robotNode; @@ -828,9 +828,9 @@ namespace VirtualRobot std::vector< ChildFromRobotDef > childrenFromRobot = iter->second; RobotNodePtr node = iter->first; - for (unsigned int i = 0; i < childrenFromRobot.size(); i++) + for (auto & i : childrenFromRobot) { - boost::filesystem::path filenameNew(childrenFromRobot[i].filename); + boost::filesystem::path filenameNew(i.filename); boost::filesystem::path filenameBasePath(basePath); boost::filesystem::path filenameNewComplete = boost::filesystem::operator/(filenameBasePath, filenameNew); @@ -846,27 +846,27 @@ namespace VirtualRobot } RobotPtr r = loadRobot(filenameNewComplete.string(), loadMode); - THROW_VR_EXCEPTION_IF(!r, "Could not add child-from-robot due to failed loading of robot from file" << childrenFromRobot[i].filename); + THROW_VR_EXCEPTION_IF(!r, "Could not add child-from-robot due to failed loading of robot from file" << i.filename); RobotNodePtr root = r->getRootNode(); - THROW_VR_EXCEPTION_IF(!root, "Could not add child-from-robot. No root node in file" << childrenFromRobot[i].filename); + THROW_VR_EXCEPTION_IF(!root, "Could not add child-from-robot. No root node in file" << i.filename); RobotNodePtr rootNew = root->clone(robo, true, node); - THROW_VR_EXCEPTION_IF(!rootNew, "Clone failed. Could not add child-from-robot from file " << childrenFromRobot[i].filename); + THROW_VR_EXCEPTION_IF(!rootNew, "Clone failed. Could not add child-from-robot from file " << i.filename); std::vector<EndEffectorPtr> eefs; r->getEndEffectors(eefs); - for (std::vector<EndEffectorPtr>::iterator eef = eefs.begin(); eef != eefs.end(); eef++) + for (auto & eef : eefs) { - (*eef)->clone(robo); + eef->clone(robo); } std::vector<RobotNodeSetPtr> nodeSets; r->getRobotNodeSets(nodeSets); - for (std::vector<RobotNodeSetPtr>::iterator ns = nodeSets.begin(); ns != nodeSets.end(); ns++) + for (auto & nodeSet : nodeSets) { - (*ns)->clone(robo); + nodeSet->clone(robo); } // already performed in root->clone @@ -877,17 +877,17 @@ namespace VirtualRobot } //std::vector<RobotNodeSetPtr> robotNodeSets - for (unsigned int i = 0; i < endeffectorNodes.size(); ++i) + for (auto & endeffectorNode : endeffectorNodes) { - EndEffectorPtr eef = processEndeffectorNode(endeffectorNodes[i], robo); + EndEffectorPtr eef = processEndeffectorNode(endeffectorNode, robo); robo->registerEndEffector(eef); } int rnsCounter = 0; - for (std::size_t i = 0; i < robotNodeSetNodes.size(); ++i) + for (auto & robotNodeSetNode : robotNodeSetNodes) { - RobotNodeSetPtr rns = processRobotNodeSet(robotNodeSetNodes[i], robo, robotRoot, rnsCounter); + RobotNodeSetPtr rns = processRobotNodeSet(robotNodeSetNode, robo, robotRoot, rnsCounter); //nodeSets.push_back(rns); } @@ -895,11 +895,11 @@ namespace VirtualRobot robo->getRobotNodes(nodes); RobotNodePtr root = robo->getRootNode(); - for (size_t i = 0; i < nodes.size(); i++) + for (auto & node : nodes) { - if (nodes[i] != root && !(nodes[i]->getParent())) + if (node != root && !(node->getParent())) { - THROW_VR_EXCEPTION("Node without parent: " << nodes[i]->getName()); + THROW_VR_EXCEPTION("Node without parent: " << node->getName()); } } @@ -1038,9 +1038,9 @@ namespace VirtualRobot else { // double name check - for (unsigned int i = 0; i < robotNodes.size(); i++) + for (auto & robotNode : robotNodes) { - THROW_VR_EXCEPTION_IF((robotNodes[i]->getName() == n->getName()), "At least two RobotNodes with name <" << n->getName() << "> defined in robot definition"); + THROW_VR_EXCEPTION_IF((robotNode->getName() == n->getName()), "At least two RobotNodes with name <" << n->getName() << "> defined in robot definition"); } childrenMap[n] = childrenNames; @@ -1506,9 +1506,9 @@ namespace VirtualRobot { std::vector<RobotNodePtr> nodes = robot->getRobotNodes(); - for (size_t i = 0; i < nodes.size(); i++) + for (auto & node : nodes) { - nodes[i]->saveModelFiles(modelDirComplete.string(), true); + node->saveModelFiles(modelDirComplete.string(), true); } } diff --git a/VirtualRobot/XML/SceneIO.cpp b/VirtualRobot/XML/SceneIO.cpp index d573bf1c45d0d347a68039ef6bc7086910c9b026..05a9c6d5ffdf55aad7ce871978cc0b6935007fdc 100644 --- a/VirtualRobot/XML/SceneIO.cpp +++ b/VirtualRobot/XML/SceneIO.cpp @@ -123,10 +123,10 @@ namespace VirtualRobot // create & register node sets int rnsNr = 0; - for (size_t i = 0; i < rnsNodes.size(); i++) + for (auto & rnsNode : rnsNodes) { // registers rns to robot - RobotNodeSetPtr r = processRobotNodeSet(rnsNodes[i], robot, robot->getRootNode()->getName(), rnsNr); + RobotNodeSetPtr r = processRobotNodeSet(rnsNode, robot, robot->getRootNode()->getName(), rnsNr); THROW_VR_EXCEPTION_IF(!r, "Invalid RobotNodeSet definition " << endl); } @@ -316,9 +316,9 @@ namespace VirtualRobot } // process all sceneSetNodes - for (size_t i = 0; i < sceneSetNodes.size(); i++) + for (auto & sceneSetNode : sceneSetNodes) { - bool r = processSceneObjectSet(sceneSetNodes[i], scene); + bool r = processSceneObjectSet(sceneSetNode, scene); if (!r) { @@ -329,9 +329,9 @@ namespace VirtualRobot // process all trajectories - for (size_t i = 0; i < trajectoryNodes.size(); i++) + for (auto & trajectoryNode : trajectoryNodes) { - bool r = processSceneTrajectory(trajectoryNodes[i], scene); + bool r = processSceneTrajectory(trajectoryNode, scene); if (!r) { diff --git a/VirtualRobot/examples/CameraViewer/showCamWindow.cpp b/VirtualRobot/examples/CameraViewer/showCamWindow.cpp index 4e3cc38beccdedf675f7abf8cb855cfc7e3a172c..5fea4e9cf88e2ada3186d24822f38ac5982f2424 100644 --- a/VirtualRobot/examples/CameraViewer/showCamWindow.cpp +++ b/VirtualRobot/examples/CameraViewer/showCamWindow.cpp @@ -256,9 +256,9 @@ void showCamWindow::updateJointBox() { UI.comboBoxJoint->clear(); - for (unsigned int i = 0; i < currentRobotNodes.size(); i++) + for (auto & currentRobotNode : currentRobotNodes) { - UI.comboBoxJoint->addItem(QString(currentRobotNodes[i]->getName().c_str())); + UI.comboBoxJoint->addItem(QString(currentRobotNode->getName().c_str())); } } @@ -275,9 +275,9 @@ void showCamWindow::updateRNSBox() UI.comboBoxRobotNodeSet->clear(); UI.comboBoxRobotNodeSet->addItem(QString("<All>")); - for (unsigned int i = 0; i < robotNodeSets.size(); i++) + for (auto & robotNodeSet : robotNodeSets) { - UI.comboBoxRobotNodeSet->addItem(QString(robotNodeSets[i]->getName().c_str())); + UI.comboBoxRobotNodeSet->addItem(QString(robotNodeSet->getName().c_str())); } } diff --git a/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp b/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp index 3237ac7f26394a4e2acaa9fb3e2242167555da8e..d034722ffd7965dd9dcfc475dcd10ec643737fcf 100644 --- a/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp +++ b/VirtualRobot/examples/ConstrainedIK/ConstrainedIKWindow.cpp @@ -216,12 +216,12 @@ void ConstrainedIKWindow::updateKCBox() robot->getRobotNodeSets(rns); kinChains.clear(); - for (unsigned int i = 0; i < rns.size(); i++) + for (auto & rn : rns) { - if (rns[i]->isKinematicChain()) + if (rn->isKinematicChain()) { - UI.comboBoxKC->addItem(QString(rns[i]->getName().c_str())); - kinChains.push_back(rns[i]); + UI.comboBoxKC->addItem(QString(rn->getName().c_str())); + kinChains.push_back(rn); } } } diff --git a/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp b/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp index c5cc008d624e97570b70399befdbfedcbbcf891a..f3fff8b02f78b6b9b21377681e42ab997bdce400 100644 --- a/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp +++ b/VirtualRobot/examples/GenericIK/GenericIKWindow.cpp @@ -246,12 +246,12 @@ void GenericIKWindow::updateKCBox() robot->getRobotNodeSets(rns); kinChains.clear(); - for (unsigned int i = 0; i < rns.size(); i++) + for (auto & rn : rns) { - if (rns[i]->isKinematicChain()) + if (rn->isKinematicChain()) { - UI.comboBoxKC->addItem(QString(rns[i]->getName().c_str())); - kinChains.push_back(rns[i]); + UI.comboBoxKC->addItem(QString(rn->getName().c_str())); + kinChains.push_back(rn); } } } @@ -428,9 +428,9 @@ void GenericIKWindow::solve() cout << "Joint values:" << endl; std::vector<RobotNodePtr> nodes = kc->getAllRobotNodes(); - for (size_t i = 0; i < nodes.size(); i++) + for (auto & node : nodes) { - cout << nodes[i]->getJointValue() << endl; + cout << node->getJointValue() << endl; } /* diff --git a/VirtualRobot/examples/Jacobi/JacobiWindow.cpp b/VirtualRobot/examples/Jacobi/JacobiWindow.cpp index 6fa2a35f5367cea99f29e0be98fbf1d1bf0ecf87..f858dbf878fd5a681fd8c445da05f1f597463538 100644 --- a/VirtualRobot/examples/Jacobi/JacobiWindow.cpp +++ b/VirtualRobot/examples/Jacobi/JacobiWindow.cpp @@ -330,12 +330,12 @@ void JacobiWindow::updateKCBox() robot->getRobotNodeSets(rns); kinChains.clear(); - for (unsigned int i = 0; i < rns.size(); i++) + for (auto & rn : rns) { - if (rns[i]->isKinematicChain()) + if (rn->isKinematicChain()) { - UI.comboBoxKC->addItem(QString(rns[i]->getName().c_str())); - kinChains.push_back(rns[i]); + UI.comboBoxKC->addItem(QString(rn->getName().c_str())); + kinChains.push_back(rn); } } } @@ -369,26 +369,26 @@ void JacobiWindow::selectKC(int nr) std::vector<RobotNodePtr> nodes = kc->getAllRobotNodes(); elbow.reset(); - for (size_t i = 0; i < nodes.size(); i++) + for (auto & node : nodes) { - if ((nodes[i])->getName() == std::string("Elbow L")) + if (node->getName() == std::string("Elbow L")) { - elbow = nodes[i]; + elbow = node; } - if ((nodes[i])->getName() == std::string("Elbow R")) + if (node->getName() == std::string("Elbow R")) { - elbow = nodes[i]; + elbow = node; } - if ((nodes[i])->getName() == std::string("TCP L")) + if (node->getName() == std::string("TCP L")) { - elbow = nodes[i]; + elbow = node; } - if ((nodes[i])->getName() == std::string("TCP R")) + if (node->getName() == std::string("TCP R")) { - elbow = nodes[i]; + elbow = node; } } diff --git a/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp b/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp index 4c2d65fd0d1eae321222a6d165fab203a752c3f8..b1b7b4c3a94cd6561907a5de4ffbed2f811068fd 100644 --- a/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp +++ b/VirtualRobot/examples/ReachabilityMap/ReachabilityMapWindow.cpp @@ -485,9 +485,9 @@ void ReachabilityMapWindow::updateEEFBox() std::vector<EndEffectorPtr> eefs = robot->getEndEffectors(); - for (unsigned int i = 0; i < eefs.size(); i++) + for (auto & eef : eefs) { - UI.comboBoxEEF->addItem(QString(eefs[i]->getName().c_str())); + UI.comboBoxEEF->addItem(QString(eef->getName().c_str())); } selectEEF(0); diff --git a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp index e17e88ed7a3f8543e1a22c196c6f789f371c4533..0b0a9d9de2176b186e9352c62072c7c126d88d34 100644 --- a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp +++ b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp @@ -287,10 +287,10 @@ void showRobotWindow::showSensors() std::vector<SensorPtr> sensors = robot->getSensors(); - for (size_t i = 0; i < sensors.size(); i++) + for (auto & sensor : sensors) { - sensors[i]->setupVisualization(showSensors, showSensors); - sensors[i]->showCoordinateSystem(showSensors); + sensor->setupVisualization(showSensors, showSensors); + sensor->showCoordinateSystem(showSensors); } // rebuild visualization @@ -547,9 +547,9 @@ void showRobotWindow::updateJointBox() { UI.comboBoxJoint->clear(); - for (unsigned int i = 0; i < currentRobotNodes.size(); i++) + for (auto & currentRobotNode : currentRobotNodes) { - UI.comboBoxJoint->addItem(QString(currentRobotNodes[i]->getName().c_str())); + UI.comboBoxJoint->addItem(QString(currentRobotNode->getName().c_str())); } } @@ -558,9 +558,9 @@ void showRobotWindow::updateRNSBox() UI.comboBoxRobotNodeSet->clear(); UI.comboBoxRobotNodeSet->addItem(QString("<All>")); - for (unsigned int i = 0; i < robotNodeSets.size(); i++) + for (auto & robotNodeSet : robotNodeSets) { - UI.comboBoxRobotNodeSet->addItem(QString(robotNodeSets[i]->getName().c_str())); + UI.comboBoxRobotNodeSet->addItem(QString(robotNodeSet->getName().c_str())); } } @@ -1075,9 +1075,9 @@ void showRobotWindow::selectEEF(int nr) std::vector<std::string> ps = currentEEF->getPreshapes(); UI.comboBoxEndEffectorPS->addItem(QString("none")); - for (unsigned int i = 0; i < ps.size(); i++) + for (auto & p : ps) { - UI.comboBoxEndEffectorPS->addItem(QString(ps[i].c_str())); + UI.comboBoxEndEffectorPS->addItem(QString(p.c_str())); } } @@ -1105,8 +1105,8 @@ void showRobotWindow::updateEEFBox() { UI.comboBoxEndEffector->clear(); - for (unsigned int i = 0; i < eefs.size(); i++) + for (auto & eef : eefs) { - UI.comboBoxEndEffector->addItem(QString(eefs[i]->getName().c_str())); + UI.comboBoxEndEffector->addItem(QString(eef->getName().c_str())); } } diff --git a/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp b/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp index 253805552500280ca133ddbeecbde232931e8776..83d876bb5498baaf80115ff5352160873192f94d 100644 --- a/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp +++ b/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp @@ -405,9 +405,9 @@ void showSceneWindow::selectRobot(int nr) std::vector<VirtualRobot::RobotConfigPtr> roc = scene->getRobotConfigs(currentRobot); - for (size_t i = 0; i < roc.size(); i++) + for (auto & i : roc) { - QString rn = roc[i]->getName().c_str(); + QString rn = i->getName().c_str(); UI.comboBoxRobotConfig->addItem(rn); } @@ -418,9 +418,9 @@ void showSceneWindow::selectRobot(int nr) std::vector<VirtualRobot::TrajectoryPtr> tr = scene->getTrajectories(currentRobot->getName()); - for (size_t i = 0; i < tr.size(); i++) + for (auto & i : tr) { - QString rn = tr[i]->getName().c_str(); + QString rn = i->getName().c_str(); UI.comboBoxTrajectory->addItem(rn); } @@ -432,9 +432,9 @@ void showSceneWindow::selectRobot(int nr) std::vector<VirtualRobot::EndEffectorPtr> eefs = currentRobot->getEndEffectors(); - for (size_t i = 0; i < eefs.size(); i++) + for (auto & eef : eefs) { - QString rn = eefs[i]->getName().c_str(); + QString rn = eef->getName().c_str(); UI.comboBoxEEF->addItem(rn); } @@ -549,25 +549,25 @@ void showSceneWindow::updateGui() std::vector<VirtualRobot::RobotPtr> robs = scene->getRobots(); - for (size_t i = 0; i < robs.size(); i++) + for (auto & rob : robs) { - QString rn = robs[i]->getName().c_str(); + QString rn = rob->getName().c_str(); UI.comboBoxRobot->addItem(rn); } std::vector<VirtualRobot::ManipulationObjectPtr> mos = scene->getManipulationObjects(); - for (size_t i = 0; i < mos.size(); i++) + for (auto & mo : mos) { - QString mn = mos[i]->getName().c_str(); + QString mn = mo->getName().c_str(); UI.comboBoxObject->addItem(mn); } std::vector<VirtualRobot::ObstaclePtr> obs = scene->getObstacles(); - for (size_t i = 0; i < obs.size(); i++) + for (auto & ob : obs) { - QString on = obs[i]->getName().c_str(); + QString on = ob->getName().c_str(); UI.comboBoxObject->addItem(on); } diff --git a/VirtualRobot/examples/reachability/reachabilityWindow.cpp b/VirtualRobot/examples/reachability/reachabilityWindow.cpp index 80d9620ed2fde1c5b15c9e7806a07ef213a49cfa..fe46da502ee0ea73d4279fa6831c286665591ba2 100644 --- a/VirtualRobot/examples/reachability/reachabilityWindow.cpp +++ b/VirtualRobot/examples/reachability/reachabilityWindow.cpp @@ -272,9 +272,9 @@ void reachabilityWindow::updateRNSBox() UI.comboBoxRNS->clear(); //UI.comboBoxRNS->addItem(QString("<All>")); - for (unsigned int i = 0; i < robotNodeSets.size(); i++) + for (auto & robotNodeSet : robotNodeSets) { - UI.comboBoxRNS->addItem(QString(robotNodeSets[i]->getName().c_str())); + UI.comboBoxRNS->addItem(QString(robotNodeSet->getName().c_str())); } selectRNS(0); @@ -314,9 +314,9 @@ void reachabilityWindow::updateJointBox() { UI.comboBoxJoint->clear(); - for (unsigned int i = 0; i < allRobotNodes.size(); i++) + for (auto & allRobotNode : allRobotNodes) { - UI.comboBoxJoint->addItem(QString(allRobotNodes[i]->getName().c_str())); + UI.comboBoxJoint->addItem(QString(allRobotNode->getName().c_str())); } selectJoint(0); @@ -427,16 +427,16 @@ void reachabilityWindow::loadRobot() robot->getRobotNodeSets(allRNS); robotNodeSets.clear(); - for (size_t i = 0; i < allRNS.size(); i++) + for (auto & i : allRNS) { - if (allRNS[i]->isKinematicChain()) + if (i->isKinematicChain()) { - VR_INFO << " RNS <" << allRNS[i]->getName() << "> is a valid kinematic chain" << endl; - robotNodeSets.push_back(allRNS[i]); + VR_INFO << " RNS <" << i->getName() << "> is a valid kinematic chain" << endl; + robotNodeSets.push_back(i); } else { - VR_INFO << " RNS <" << allRNS[i]->getName() << "> is not a valid kinematic chain" << endl; + VR_INFO << " RNS <" << i->getName() << "> is not a valid kinematic chain" << endl; } } @@ -514,10 +514,10 @@ void reachabilityWindow::createReach() std::vector < VirtualRobot::RobotNodeSetPtr > allRNS; robot->getRobotNodeSets(allRNS); - for (size_t i = 0; i < allRNS.size(); i++) + for (auto & i : allRNS) { - UICreate.comboBoxColModelDynamic->addItem(QString(allRNS[i]->getName().c_str())); - UICreate.comboBoxColModelStatic->addItem(QString(allRNS[i]->getName().c_str())); + UICreate.comboBoxColModelDynamic->addItem(QString(i->getName().c_str())); + UICreate.comboBoxColModelStatic->addItem(QString(i->getName().c_str())); } UICreate.comboBoxQualityMeasure->addItem(QString("Reachability")); diff --git a/VirtualRobot/examples/stability/stabilityWindow.cpp b/VirtualRobot/examples/stability/stabilityWindow.cpp index 7559c1166f01f118bce5cc579f33a533098848ff..82c5edeb43f82af04263648c2ab15e414d915721 100644 --- a/VirtualRobot/examples/stability/stabilityWindow.cpp +++ b/VirtualRobot/examples/stability/stabilityWindow.cpp @@ -349,10 +349,10 @@ void stabilityWindow::updateSupportVisu() std::vector< Eigen::Vector2f > points2D; //MathTools::Plane plane2(Eigen::Vector3f(0,0,0),Eigen::Vector3f(0,1.0f,0)); - for (size_t u = 0; u < points.size(); u++) + for (auto & point : points) { - Eigen::Vector2f pt2d = MathTools::projectPointToPlane2D(points[u].p, p); + Eigen::Vector2f pt2d = MathTools::projectPointToPlane2D(point.p, p); points2D.push_back(pt2d); } @@ -371,13 +371,13 @@ void stabilityWindow::updateRNSBox() robot->getRobotNodeSets(allRNS); robotNodeSets.clear(); - for (size_t i = 0; i < allRNS.size(); i++) + for (auto & i : allRNS) { //if (allRNS[i]->isKinematicChain()) //{ //VR_INFO << " RNS <" << allRNS[i]->getName() << "> is a valid kinematic chain" << endl; - robotNodeSets.push_back(allRNS[i]); - UI.comboBoxRNS->addItem(QString(allRNS[i]->getName().c_str())); + 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; @@ -385,9 +385,9 @@ void stabilityWindow::updateRNSBox() } - for (unsigned int i = 0; i < allRobotNodes.size(); i++) + for (auto & allRobotNode : allRobotNodes) { - allRobotNodes[i]->showBoundingBox(false); + allRobotNode->showBoundingBox(false); } @@ -447,9 +447,9 @@ void stabilityWindow::updateJointBox() { UI.comboBoxJoint->clear(); - for (unsigned int i = 0; i < currentRobotNodes.size(); i++) + for (auto & currentRobotNode : currentRobotNodes) { - UI.comboBoxJoint->addItem(QString(currentRobotNodes[i]->getName().c_str())); + UI.comboBoxJoint->addItem(QString(currentRobotNode->getName().c_str())); } selectJoint(0); diff --git a/VirtualRobot/tests/VirtualRobotWorkSpaceTest.cpp b/VirtualRobot/tests/VirtualRobotWorkSpaceTest.cpp index 55db998f0218b69fa8bf24044ad0c83911216bb7..86eb0b82390b0c2f179d40463ce4f57ea1441507 100644 --- a/VirtualRobot/tests/VirtualRobotWorkSpaceTest.cpp +++ b/VirtualRobot/tests/VirtualRobotWorkSpaceTest.cpp @@ -50,9 +50,9 @@ BOOST_AUTO_TEST_CASE(testWorkSpaceEuler) BOOST_CHECK_SMALL(x[5], 1e-6f); // identity, vector -> matrix - for (int i = 0; i < 6; i++) + for (float & i : x) { - x[i] = 0.0f; + i = 0.0f; } ws->vector2Matrix(x, m);