Robot: modernize C++: use range-based for loop
This commit is contained in:
@@ -75,8 +75,8 @@ App::DocumentObjectExecReturn *Edge2TracObject::execute()
|
||||
std::vector<TopoDS_Edge> edges;
|
||||
|
||||
// run through the edge name and get the real objects from the TopoShape
|
||||
for (std::vector<std::string>::const_iterator it= SubVals.begin();it!=SubVals.end();++it) {
|
||||
TopoDS_Edge edge = TopoDS::Edge(TopShape.getSubShape(it->c_str()));
|
||||
for (const auto & SubVal : SubVals) {
|
||||
TopoDS_Edge edge = TopoDS::Edge(TopShape.getSubShape(SubVal.c_str()));
|
||||
edges.push_back(edge);
|
||||
}
|
||||
|
||||
@@ -90,20 +90,20 @@ App::DocumentObjectExecReturn *Edge2TracObject::execute()
|
||||
// set the number of cluster and edges
|
||||
NbrOfCluster = aclusteroutput.size();
|
||||
NbrOfEdges = 0;
|
||||
for(std::vector<std::vector<TopoDS_Edge> >::const_iterator it=aclusteroutput.begin();it!=aclusteroutput.end();++it)
|
||||
NbrOfEdges += it->size();
|
||||
for(const auto & it : aclusteroutput)
|
||||
NbrOfEdges += it.size();
|
||||
|
||||
// trajectory to fill
|
||||
Robot::Trajectory trac;
|
||||
bool first = true;
|
||||
|
||||
// cycle through the cluster
|
||||
for(std::vector<std::vector<TopoDS_Edge> >::const_iterator it=aclusteroutput.begin();it!=aclusteroutput.end();++it)
|
||||
for(const auto & it : aclusteroutput)
|
||||
{
|
||||
// cycle through the edges of the cluster
|
||||
for(std::vector<TopoDS_Edge>::const_iterator it2=it->begin();it2!=it->end();++it2)
|
||||
for(const auto& it2 : it)
|
||||
{
|
||||
BRepAdaptor_Curve adapt(*it2);
|
||||
BRepAdaptor_Curve adapt(it2);
|
||||
|
||||
switch(adapt.GetType())
|
||||
{
|
||||
@@ -125,7 +125,7 @@ App::DocumentObjectExecReturn *Edge2TracObject::execute()
|
||||
}
|
||||
|
||||
// if reverse orintation, switch the points
|
||||
if ( it2->Orientation() == TopAbs_REVERSED )
|
||||
if ( it2.Orientation() == TopAbs_REVERSED )
|
||||
{
|
||||
//switch the points and orientation
|
||||
gp_Pnt tmpP = P1;
|
||||
@@ -154,7 +154,7 @@ App::DocumentObjectExecReturn *Edge2TracObject::execute()
|
||||
Standard_Real end = adapt.LastParameter();
|
||||
Standard_Real stp = ParLength / NbrSegments;
|
||||
bool reversed = false;
|
||||
if (it2->Orientation() == TopAbs_REVERSED) {
|
||||
if (it2.Orientation() == TopAbs_REVERSED) {
|
||||
std::swap(beg, end);
|
||||
stp = - stp;
|
||||
reversed = true;
|
||||
@@ -205,7 +205,7 @@ App::DocumentObjectExecReturn *Edge2TracObject::execute()
|
||||
Standard_Real NbrSegments = Round(Length / SegValue.getValue());
|
||||
Standard_Real SegLength = ParLength / NbrSegments;
|
||||
|
||||
if ( it2->Orientation() == TopAbs_REVERSED )
|
||||
if ( it2.Orientation() == TopAbs_REVERSED )
|
||||
{
|
||||
//Beginning and End switch
|
||||
double i = adapt.LastParameter();
|
||||
@@ -252,9 +252,6 @@ App::DocumentObjectExecReturn *Edge2TracObject::execute()
|
||||
default:
|
||||
throw Base::TypeError("Unknown Edge type in Robot::Edge2TracObject::execute()");
|
||||
}
|
||||
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
@@ -271,6 +268,5 @@ App::DocumentObjectExecReturn *Edge2TracObject::execute()
|
||||
|
||||
void Edge2TracObject::onChanged(const Property* prop)
|
||||
{
|
||||
|
||||
App::GeoFeature::onChanged(prop);
|
||||
}
|
||||
|
||||
@@ -141,21 +141,21 @@ void Robot6Axis::readKinematic(const char * FileName)
|
||||
// over read the header
|
||||
in.getline(buf,119,'\n');
|
||||
// read 6 Axis
|
||||
for (int i = 0; i < 6; i++) {
|
||||
for (auto & i : temp) {
|
||||
in.getline(buf,79,'\n');
|
||||
destination.clear();
|
||||
split(std::string(buf),',',destination);
|
||||
if (destination.size() < 8)
|
||||
continue;
|
||||
// transfer the values in kinematic structure
|
||||
temp[i].a = atof(destination[0].c_str());
|
||||
temp[i].alpha = atof(destination[1].c_str());
|
||||
temp[i].d = atof(destination[2].c_str());
|
||||
temp[i].theta = atof(destination[3].c_str());
|
||||
temp[i].rotDir = atof(destination[4].c_str());
|
||||
temp[i].maxAngle = atof(destination[5].c_str());
|
||||
temp[i].minAngle = atof(destination[6].c_str());
|
||||
temp[i].velocity = atof(destination[7].c_str());
|
||||
i.a = atof(destination[0].c_str());
|
||||
i.alpha = atof(destination[1].c_str());
|
||||
i.d = atof(destination[2].c_str());
|
||||
i.theta = atof(destination[3].c_str());
|
||||
i.rotDir = atof(destination[4].c_str());
|
||||
i.maxAngle = atof(destination[5].c_str());
|
||||
i.minAngle = atof(destination[6].c_str());
|
||||
i.velocity = atof(destination[7].c_str());
|
||||
}
|
||||
|
||||
setKinematic(temp);
|
||||
|
||||
@@ -72,8 +72,8 @@ Trajectory::Trajectory(const Trajectory& Trac)
|
||||
|
||||
Trajectory::~Trajectory()
|
||||
{
|
||||
for(std::vector<Waypoint*>::iterator it = vpcWaypoints.begin();it!=vpcWaypoints.end();++it)
|
||||
delete ( *it );
|
||||
for(auto it : vpcWaypoints)
|
||||
delete it;
|
||||
delete pcTrajectory;
|
||||
}
|
||||
|
||||
@@ -82,8 +82,8 @@ Trajectory &Trajectory::operator=(const Trajectory& Trac)
|
||||
if (this == &Trac)
|
||||
return *this;
|
||||
|
||||
for(std::vector<Waypoint*>::iterator it = vpcWaypoints.begin();it!=vpcWaypoints.end();++it)
|
||||
delete ( *it );
|
||||
for(auto it : vpcWaypoints)
|
||||
delete it;
|
||||
vpcWaypoints.clear();
|
||||
vpcWaypoints.resize(Trac.vpcWaypoints.size());
|
||||
|
||||
@@ -243,11 +243,11 @@ std::string Trajectory::getUniqueWaypointName(const char *Name) const
|
||||
if (!CleanName.empty() && CleanName[0] >= 48 && CleanName[0] <= 57)
|
||||
CleanName[0] = '_';
|
||||
// strip illegal chars
|
||||
for (std::string::iterator it = CleanName.begin(); it != CleanName.end(); ++it) {
|
||||
if (!((*it>=48 && *it<=57) || // number
|
||||
(*it>=65 && *it<=90) || // uppercase letter
|
||||
(*it>=97 && *it<=122))) // lowercase letter
|
||||
*it = '_'; // it's neither number nor letter
|
||||
for (char & it : CleanName) {
|
||||
if (!((it>=48 && it<=57) || // number
|
||||
(it>=65 && it<=90) || // uppercase letter
|
||||
(it>=97 && it<=122))) // lowercase letter
|
||||
it = '_'; // it's neither number nor letter
|
||||
}
|
||||
|
||||
// name in use?
|
||||
|
||||
@@ -48,11 +48,11 @@ App::DocumentObjectExecReturn *TrajectoryCompound::execute()
|
||||
const std::vector<DocumentObject*> &Tracs = Source.getValues();
|
||||
Robot::Trajectory result;
|
||||
|
||||
for (std::vector<DocumentObject*>::const_iterator it= Tracs.begin();it!=Tracs.end();++it) {
|
||||
if ((*it)->getTypeId().isDerivedFrom(Robot::TrajectoryObject::getClassTypeId())){
|
||||
const std::vector<Waypoint*> &wps = static_cast<Robot::TrajectoryObject*>(*it)->Trajectory.getValue().getWaypoints();
|
||||
for (std::vector<Waypoint*>::const_iterator it2= wps.begin();it2!=wps.end();++it2) {
|
||||
result.addWaypoint(**it2);
|
||||
for (auto it : Tracs) {
|
||||
if (it->getTypeId().isDerivedFrom(Robot::TrajectoryObject::getClassTypeId())){
|
||||
const std::vector<Waypoint*> &wps = static_cast<Robot::TrajectoryObject*>(it)->Trajectory.getValue().getWaypoints();
|
||||
for (auto wp : wps) {
|
||||
result.addWaypoint(*wp);
|
||||
}
|
||||
}else
|
||||
return new App::DocumentObjectExecReturn("Not all objects in compound are trajectories!");
|
||||
|
||||
@@ -65,8 +65,8 @@ App::DocumentObjectExecReturn* TrajectoryDressUpObject::execute()
|
||||
return new App::DocumentObjectExecReturn("Linked object is not a Trajectory object");
|
||||
|
||||
const std::vector<Waypoint*>& wps = static_cast<Robot::TrajectoryObject*>(link)->Trajectory.getValue().getWaypoints();
|
||||
for (std::vector<Waypoint*>::const_iterator it = wps.begin(); it != wps.end(); ++it) {
|
||||
Waypoint wpt = **it;
|
||||
for (auto wp : wps) {
|
||||
Waypoint wpt = *wp;
|
||||
if (UseSpeed.getValue())
|
||||
wpt.Velocity = Speed.getValue();
|
||||
if (UseAcceleration.getValue())
|
||||
|
||||
Reference in New Issue
Block a user