fix some typos

This commit is contained in:
wmayer 2016-09-27 19:26:45 +02:00
parent 17476b25dc
commit 81a6d4f4cc
5 changed files with 42 additions and 42 deletions

View File

@ -851,7 +851,7 @@ void MeshObject::offsetSpecial2(float fSize)
}
}
// if there no flipped triangels -> stop
// if there are no flipped triangles -> stop
//int f =fliped.size();
if (fliped.size() == 0)
break;

View File

@ -98,7 +98,7 @@ void MeshAlgos::offsetSpecial2(MeshCore::MeshKernel* Mesh, float fSize)
}
}
// if there no flipped triangels -> stop
// if there are no flipped triangles -> stop
//int f =fliped.size();
if(fliped.size() == 0)
break;

View File

@ -215,7 +215,7 @@ PROPERTY_SOURCE(PartDesign::Cylinder, PartDesign::FeaturePrimitive)
Cylinder::Cylinder()
{
ADD_PROPERTY_TYPE(Radius,(10.0f),"Cylinder",App::Prop_None,"The radius of the cylinder");
ADD_PROPERTY_TYPE(Angle,(360.0f),"Cylinder",App::Prop_None,"The closing angel of the cylinder ");
ADD_PROPERTY_TYPE(Angle,(360.0f),"Cylinder",App::Prop_None,"The closing angle of the cylinder ");
ADD_PROPERTY_TYPE(Height,(10.0f),"Cylinder",App::Prop_None,"The height of the cylinder");
Angle.setConstraints(&angleRangeU);
Radius.setConstraints(&quantityRange);

View File

@ -33,11 +33,11 @@
#include "kdl_cp/chainfksolver.hpp"
#include "kdl_cp/chainfksolverpos_recursive.hpp"
#include "kdl_cp/frames_io.hpp"
#include "kdl_cp/chainiksolver.hpp"
#include "kdl_cp/chainiksolvervel_pinv.hpp"
#include "kdl_cp/chainjnttojacsolver.hpp"
#include "kdl_cp/chainiksolverpos_nr.hpp"
#include "kdl_cp/chainiksolverpos_nr_jl.hpp"
#include "kdl_cp/chainiksolver.hpp"
#include "kdl_cp/chainiksolvervel_pinv.hpp"
#include "kdl_cp/chainjnttojacsolver.hpp"
#include "kdl_cp/chainiksolverpos_nr.hpp"
#include "kdl_cp/chainiksolverpos_nr_jl.hpp"
#include "Robot6Axis.h"
#include "RobotAlgos.h"
@ -53,28 +53,28 @@
using namespace Robot;
using namespace Base;
using namespace KDL;
// some default roboter
AxisDefinition KukaIR500[6] = {
// a ,alpha ,d ,theta ,rotDir ,maxAngle ,minAngle ,AxisVelocity
{500 ,-90 ,1045 ,0 , -1 ,+185 ,-185 ,156 }, // Axis 1
{1300 ,0 ,0 ,0 , 1 ,+35 ,-155 ,156 }, // Axis 2
{55 ,+90 ,0 ,-90 , 1 ,+154 ,-130 ,156 }, // Axis 3
{0 ,-90 ,-1025,0 , 1 ,+350 ,-350 ,330 }, // Axis 4
{0 ,+90 ,0 ,0 , 1 ,+130 ,-130 ,330 }, // Axis 5
{0 ,+180 ,-300 ,0 , 1 ,+350 ,-350 ,615 } // Axis 6
};
// some default roboter
AxisDefinition KukaIR500[6] = {
// a ,alpha ,d ,theta ,rotDir ,maxAngle ,minAngle ,AxisVelocity
{500 ,-90 ,1045 ,0 , -1 ,+185 ,-185 ,156 }, // Axis 1
{1300 ,0 ,0 ,0 , 1 ,+35 ,-155 ,156 }, // Axis 2
{55 ,+90 ,0 ,-90 , 1 ,+154 ,-130 ,156 }, // Axis 3
{0 ,-90 ,-1025,0 , 1 ,+350 ,-350 ,330 }, // Axis 4
{0 ,+90 ,0 ,0 , 1 ,+130 ,-130 ,330 }, // Axis 5
{0 ,+180 ,-300 ,0 , 1 ,+350 ,-350 ,615 } // Axis 6
};
TYPESYSTEM_SOURCE(Robot::Robot6Axis , Base::Persistence);
Robot6Axis::Robot6Axis()
{
// create joint array for the min and max angel values of each joint
Min = JntArray(6);
Max = JntArray(6);
// create joint array for the min and max angle values of each joint
Min = JntArray(6);
Max = JntArray(6);
// Create joint array
Actuall = JntArray(6);
@ -89,21 +89,21 @@ Robot6Axis::~Robot6Axis()
void Robot6Axis::setKinematic(const AxisDefinition KinDef[6])
{
Chain temp;
for(int i=0 ; i<6 ;i++){
temp.addSegment(Segment(Joint(Joint::RotZ),Frame::DH(KinDef[i].a ,KinDef[i].alpha * (M_PI/180) ,KinDef[i].d ,KinDef[i].theta * (M_PI/180) )));
RotDir [i] = KinDef[i].rotDir;
Max(i) = KinDef[i].maxAngle * (M_PI/180);
Min(i) = KinDef[i].minAngle * (M_PI/180);
Velocity[i] = KinDef[i].velocity;
}
// for now and testing
Kinematic = temp;
// get the actuall TCP out of tha axis
Chain temp;
for(int i=0 ; i<6 ;i++){
temp.addSegment(Segment(Joint(Joint::RotZ),Frame::DH(KinDef[i].a ,KinDef[i].alpha * (M_PI/180) ,KinDef[i].d ,KinDef[i].theta * (M_PI/180) )));
RotDir [i] = KinDef[i].rotDir;
Max(i) = KinDef[i].maxAngle * (M_PI/180);
Min(i) = KinDef[i].minAngle * (M_PI/180);
Velocity[i] = KinDef[i].velocity;
}
// for now and testing
Kinematic = temp;
// get the actuall TCP out of tha axis
calcTcp();
}
@ -208,7 +208,7 @@ void Robot6Axis::Restore(XMLReader &reader)
reader.getAttributeAsFloat("Q1"),
reader.getAttributeAsFloat("Q2"),
reader.getAttributeAsFloat("Q3")));
Temp.addSegment(Segment(Joint(Joint::RotZ),toFrame(Tip)));
Temp.addSegment(Segment(Joint(Joint::RotZ),toFrame(Tip)));
if(reader.hasAttribute("rotDir"))

View File

@ -53,7 +53,7 @@
// 2) EulerZYX,EulerZYZ,RPY word followed by a vector, e.g. :
// Eulerzyx[10,20,30]
// (ANGLES are always expressed in DEGREES for I/O)
// (ANGELS are always expressed in RADIANS for internal representation)
// (ANGLES are always expressed in RADIANS for internal representation)
// 3) Rot [1,2,3] [20] Rotates around axis [1,2,3] with an angle
// of 20 degrees.
// 4) Identity returns identity rotation matrix.