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 PyObject * | getPyObject () |
This method returns the Python wrapper for a C++ object. More... | |
virtual Type | getTypeId () const |
bool | isDerivedFrom (const Type type) const |
BaseClass & | operator= (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) |
The representation for a 6-Axis industry grade robot.
Robot6Axis::Robot6Axis | ( | ) |
Robot6Axis::~Robot6Axis | ( | ) |
bool Robot6Axis::calcTcp | ( | void | ) |
double Robot6Axis::getAxis | ( | int | Axis | ) |
References Actual, and RotDir.
Referenced by Robot::RobotObject::onChanged(), Robot::Simulation::reset(), Robot::Simulation::setToTime(), and Robot::Simulation::Simulation().
double Robot6Axis::getMaxAngle | ( | int | Axis | ) |
References Max.
Referenced by RobotGui::TaskRobot6Axis::setColor(), and RobotGui::TaskRobot6Axis::setRobot().
|
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.
double Robot6Axis::getMinAngle | ( | int | Axis | ) |
References Min.
Referenced by RobotGui::TaskRobot6Axis::setRobot().
Base::Placement Robot6Axis::getTcp | ( | void | ) |
References Tcp.
Referenced by Robot::RobotObject::onChanged(), Robot::RobotObject::Restore(), RobotGui::TaskTrajectory::setTo(), and RobotGui::TrajectorySimulate::setTo().
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, setKinematic(), draftfunctions.split::split(), Robot::AxisDefinition::theta, and Robot::AxisDefinition::velocity.
Referenced by Robot::RobotObject::onChanged().
|
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 Actual, calcTcp(), Base::XMLReader::getAttributeAsFloat(), Base::XMLReader::hasAttribute(), Kinematic, Max, Min, Base::XMLReader::readElement(), Robot::toFrame(), and Velocity.
Referenced by Robot::RobotObject::Restore().
|
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.
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().
References Actual, calcTcp(), and RotDir.
Referenced by Robot::RobotObject::onChanged(), Robot::Simulation::reset(), and Robot::RobotObject::Restore().
void Robot6Axis::setKinematic | ( | const AxisDefinition | KinDef[6] | ) |
set the kinematic parameters of the robot
References calcTcp(), Kinematic, Max, Robot::AxisDefinition::maxAngle, Min, Robot::AxisDefinition::minAngle, Robot::AxisDefinition::rotDir, RotDir, Robot::AxisDefinition::velocity, and Velocity.
Referenced by readKinematic().
bool Robot6Axis::setTo | ( | const Base::Placement & | To | ) |
set the robot to that position, calculates the Axis
References Actual, Base::Placement::getPosition(), Base::Placement::getRotation(), Kinematic, Max, Min, and Tcp.
Referenced by Robot::RobotObject::onChanged(), Robot::Simulation::reset(), Robot::RobotObject::Restore(), and Robot::Simulation::setToTime().
|
protected |
|
protected |
Referenced by calcTcp(), Restore(), Save(), setKinematic(), and setTo().
|
protected |
Referenced by getMaxAngle(), Restore(), Save(), setKinematic(), and setTo().
|
protected |
Referenced by getMinAngle(), Restore(), Save(), setKinematic(), and setTo().
|
protected |
Referenced by getAxis(), Save(), setAxis(), and setKinematic().
|
protected |
Referenced by Restore(), Save(), and setKinematic().