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 () | |
![]() | |
void dumpToStream (std::ostream &stream, int compression) | |
virtual Base::Type getTypeId (void) const | |
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 SaveDocFile (Writer &) const | |
This method is used to save large amounts of data to a binary file. More... | |
![]() | |
BaseClass () | |
Construction. More... | |
virtual PyObject * getPyObject (void) | |
This method returns the Python wrapper for a C++ object. More... | |
bool isDerivedFrom (const Type type) const | |
virtual void setPyObject (PyObject *) | |
virtual ~BaseClass () | |
Destruction. More... | |
Protected Attributes | |
KDL::JntArray Actuall | |
KDL::Chain Kinematic | |
KDL::JntArray Max | |
KDL::JntArray Min | |
double RotDir [6] | |
KDL::Frame Tcp | |
double Velocity [6] | |
Additional Inherited Members | |
![]() | |
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 void * create (void) | |
static Type getClassTypeId (void) | |
static void init (void) | |
![]() | |
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
◆ getAxis()
double Robot6Axis::getAxis | ( | int | Axis | ) |
◆ getMaxAngle()
double Robot6Axis::getMaxAngle | ( | int | Axis | ) |
Referenced by RobotGui::TaskRobot6Axis::setColor(), and RobotGui::TaskRobot6Axis::setRobot().
◆ getMemSize()
|
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 | ) |
Referenced by RobotGui::TaskRobot6Axis::setRobot().
◆ getTcp()
Base::Placement Robot6Axis::getTcp | ( | void | ) |
◆ readKinematic()
void Robot6Axis::readKinematic | ( | const char * | FileName | ) |
read the kinematic parameters of the robot from a file
References Robot::AxisDefinition::a, Robot::AxisDefinition::alpha, Robot::AxisDefinition::d, Robot::AxisDefinition::maxAngle, Robot::AxisDefinition::minAngle, Robot::AxisDefinition::rotDir, Robot::AxisDefinition::theta, and Robot::AxisDefinition::velocity.
◆ Restore()
|
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:
Implements Base::Persistence.
References Base::XMLReader::getAttributeAsFloat(), Base::XMLReader::hasAttribute(), Base::XMLReader::readElement(), and Robot::toFrame().
◆ Save()
|
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:
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 Base::Placement::getPosition(), Base::Placement::getRotation(), Base::Writer::ind(), Base::Writer::Stream(), Robot::toPlacement(), Base::Vector3< _Precision >::x, Base::Vector3< _Precision >::y, and Base::Vector3< _Precision >::z.
◆ setAxis()
bool Robot6Axis::setAxis | ( | int | Axis, |
double | Value | ||
) |
◆ setKinematic()
void Robot6Axis::setKinematic | ( | const AxisDefinition | KinDef[6] | ) |
set the kinematic parameters of the robot
References Robot::AxisDefinition::maxAngle, Robot::AxisDefinition::minAngle, Robot::AxisDefinition::rotDir, and Robot::AxisDefinition::velocity.
◆ setTo()
bool Robot6Axis::setTo | ( | const Base::Placement & | To | ) |
set the robot to that position, calculates the Axis
References Base::Placement::getPosition(), and Base::Placement::getRotation().
Referenced by Robot::Simulation::reset(), Robot::Robot6AxisPy::setTcp(), and Robot::Simulation::setToTime().
Member Data Documentation
◆ Actuall
|
protected |
◆ Kinematic
|
protected |
◆ Max
|
protected |
◆ Min
|
protected |
◆ RotDir
|
protected |
◆ Tcp
|
protected |
◆ Velocity
|
protected |
The documentation for this class was generated from the following files:
- src/Mod/Robot/App/Robot6Axis.h
- src/Mod/Robot/App/Robot6Axis.cpp