Robot::Robot6Axis Class Reference

The representation for a 6-Axis industry grade robot. More...

#include <Robot6Axis.h>

Public Member Functions

bool calcTcp (void)
 calculate the new Tcp out of the Axis More...
 
double getAxis (int Axis)
 
double getMaxAngle (int Axis)
 
virtual unsigned int getMemSize (void) const
 This method is used to get the size of objects It is not meant to have the exact size, it is more or less an estimation which runs fast! Is it two bytes or a GB? More...
 
double getMinAngle (int Axis)
 
Base::Placement getTcp (void)
 
void readKinematic (const char *FileName)
 read the kinematic parameters of the robot from a file More...
 
virtual void Restore (Base::XMLReader &)
 This method is used to restore properties from an XML document. More...
 
 Robot6Axis ()
 
virtual void Save (Base::Writer &) const
 This method is used to save properties to an XML document. More...
 
bool setAxis (int Axis, double Value)
 
void setKinematic (const AxisDefinition KinDef[6])
 set the kinematic parameters of the robot More...
 
bool setTo (const Base::Placement &To)
 set the robot to that position, calculates the Axis More...
 
 ~Robot6Axis ()
 
- Public Member Functions inherited from Base::Persistence
void dumpToStream (std::ostream &stream, int compression)
 
virtual unsigned int getMemSize () const =0
 This method is used to get the size of objects It is not meant to have the exact size, it is more or less an estimation which runs fast! Is it two bytes or a GB? More...
 
virtual Base::Type getTypeId (void) const
 
virtual void Restore (XMLReader &)=0
 This method is used to restore properties from an XML document. More...
 
virtual void RestoreDocFile (Reader &)
 This method is used to restore large amounts of data from a file In this method you simply stream in your SaveDocFile() saved data. More...
 
void restoreFromStream (std::istream &stream)
 
virtual void Save (Writer &) const =0
 This method is used to save properties to an XML document. More...
 
virtual void SaveDocFile (Writer &) const
 This method is used to save large amounts of data to a binary file. More...
 
- Public Member Functions inherited from Base::BaseClass
 BaseClass ()
 Construction. More...
 
 BaseClass (const BaseClass &)=default
 
virtual PyObjectgetPyObject ()
 This method returns the Python wrapper for a C++ object. More...
 
virtual Type getTypeId () const
 
bool isDerivedFrom (const Type type) const
 
BaseClassoperator= (const BaseClass &)=default
 
virtual void setPyObject (PyObject *)
 
virtual ~BaseClass ()
 Destruction. More...
 

Protected Attributes

KDL::JntArray Actual
 
KDL::Chain Kinematic
 
KDL::JntArray Max
 
KDL::JntArray Min
 
double RotDir [6]
 
KDL::Frame Tcp
 
double Velocity [6]
 

Additional Inherited Members

- Static Public Member Functions inherited from Base::Persistence
static void * create (void)
 
static std::string encodeAttribute (const std::string &)
 Encodes an attribute upon saving. More...
 
static Base::Type getClassTypeId (void)
 
static void init (void)
 
- Static Public Member Functions inherited from Base::BaseClass
static void * create ()
 
static Type getClassTypeId ()
 
static void init ()
 
- Static Protected Member Functions inherited from Base::BaseClass
static void initSubclass (Base::Type &toInit, const char *ClassName, const char *ParentName, Type::instantiationMethod method=nullptr)
 

Detailed Description

The representation for a 6-Axis industry grade robot.

Constructor & Destructor Documentation

◆ Robot6Axis()

Robot6Axis::Robot6Axis ( )

◆ ~Robot6Axis()

Robot6Axis::~Robot6Axis ( )

Member Function Documentation

◆ calcTcp()

bool Robot6Axis::calcTcp ( void  )

calculate the new Tcp out of the Axis

References Actual, Kinematic, and Tcp.

Referenced by Restore(), setAxis(), and setKinematic().

◆ getAxis()

◆ getMaxAngle()

double Robot6Axis::getMaxAngle ( int  Axis)

◆ getMemSize()

unsigned int Robot6Axis::getMemSize ( void  ) const
virtual

This method is used to get the size of objects It is not meant to have the exact size, it is more or less an estimation which runs fast! Is it two bytes or a GB?

Implements Base::Persistence.

◆ getMinAngle()

double Robot6Axis::getMinAngle ( int  Axis)

References Min.

Referenced by RobotGui::TaskRobot6Axis::setRobot().

◆ getTcp()

◆ readKinematic()

◆ Restore()

void Robot6Axis::Restore ( Base::XMLReader )
virtual

This method is used to restore properties from an XML document.

It uses the XMLReader class, which bases on SAX, to read the in Save() written information. Again the Vector as an example:

void PropertyVector::Restore(Base::XMLReader &reader)
{
// read my Element
reader.readElement("PropertyVector");
// get the value of my Attribute
_cVec.x = reader.getAttributeAsFloat("valueX");
_cVec.y = reader.getAttributeAsFloat("valueY");
_cVec.z = reader.getAttributeAsFloat("valueZ");
}

Implements Base::Persistence.

References Actual, calcTcp(), Base::XMLReader::getAttributeAsFloat(), Base::XMLReader::hasAttribute(), Kinematic, Max, Min, Base::XMLReader::readElement(), Robot::toFrame(), and Velocity.

Referenced by Robot::RobotObject::Restore().

◆ Save()

void Robot6Axis::Save ( Base::Writer ) const
virtual

This method is used to save properties to an XML document.

A good example you'll find in PropertyStandard.cpp, e.g. the vector:

void PropertyVector::Save (Writer &writer) const
{
writer << writer.ind() << "<PropertyVector valueX=\"" << _cVec.x <<
"\" valueY=\"" << _cVec.y <<
"\" valueZ=\"" << _cVec.z <<"\"/>" << endl;
}

The writer.ind() expression writes the indentation, just for pretty printing of the XML. As you see, the writing of the XML document is not done with a DOM implementation because of performance reasons. Therefore the programmer has to take care that a valid XML document is written. This means closing tags and writing UTF-8.

See also
Base::Writer

Implements Base::Persistence.

References Actual, Base::Placement::getPosition(), Base::Placement::getRotation(), Base::Writer::ind(), Kinematic, Max, Min, RotDir, Base::Writer::Stream(), Robot::toPlacement(), Velocity, Base::Vector3< _Precision >::x, Base::Vector3< _Precision >::y, and Base::Vector3< _Precision >::z.

Referenced by Robot::RobotObject::Save().

◆ setAxis()

bool Robot6Axis::setAxis ( int  Axis,
double  Value 
)

◆ setKinematic()

void Robot6Axis::setKinematic ( const AxisDefinition  KinDef[6])

◆ setTo()

Member Data Documentation

◆ Actual

KDL::JntArray Robot::Robot6Axis::Actual
protected

◆ Kinematic

KDL::Chain Robot::Robot6Axis::Kinematic
protected

◆ Max

KDL::JntArray Robot::Robot6Axis::Max
protected

◆ Min

KDL::JntArray Robot::Robot6Axis::Min
protected

◆ RotDir

double Robot::Robot6Axis::RotDir[6]
protected

Referenced by getAxis(), Save(), setAxis(), and setKinematic().

◆ Tcp

KDL::Frame Robot::Robot6Axis::Tcp
protected

Referenced by calcTcp(), getTcp(), and setTo().

◆ Velocity

double Robot::Robot6Axis::Velocity[6]
protected

Referenced by Restore(), Save(), and setKinematic().


The documentation for this class was generated from the following files: